diff --git a/.github/workflows/build-check.yml b/.github/workflows/build-check.yml index 4dec4f0..7f0a4dc 100644 --- a/.github/workflows/build-check.yml +++ b/.github/workflows/build-check.yml @@ -4,7 +4,7 @@ jobs: run-build: runs-on: ubuntu-latest container: - image: nwdepatie/ner-gcc-arm:latest + image: ghcr.io/northeastern-electric-racing/embedded-base:main timeout-minutes: 10 steps: - name: Checkout code @@ -17,4 +17,4 @@ jobs: if ! make; then echo "The application has failed to build." exit 1 # This will cause the workflow to fail - fi \ No newline at end of file + fi diff --git a/.gitignore b/.gitignore index 9b5a1ba..97f74df 100644 --- a/.gitignore +++ b/.gitignore @@ -71,4 +71,7 @@ types_c.taghl ctrlp.root #html -*.html \ No newline at end of file +*.html + +#OS specific +.DS_Store \ No newline at end of file diff --git a/.mxproject b/.mxproject index dc02bab..3515373 100644 --- a/.mxproject +++ b/.mxproject @@ -1,25 +1,25 @@ -[PreviousLibFiles] -LibFiles=Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_can.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_rcc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_rcc_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_bus.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_rcc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_system.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_utils.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash_ramfunc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_gpio.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_gpio_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_gpio.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_dma_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_dma.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_dma.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_dmamux.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pwr.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pwr_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_pwr.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_cortex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_cortex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal.h;Drivers\STM32F4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_def.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_exti.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_exti.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_i2c.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_i2c.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_i2c_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_spi.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_tim.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_tim_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_uart.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_usart.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pcd.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pcd_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_usb.h;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_can.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ramfunc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_gpio.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_cortex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_exti.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_spi.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_uart.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_ll_usb.c;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_can.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_rcc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_rcc_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_bus.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_rcc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_system.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_utils.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_flash_ramfunc.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_gpio.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_gpio_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_gpio.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_dma_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_dma.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_dma.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_dmamux.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pwr.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pwr_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_pwr.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_cortex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_cortex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal.h;Drivers\STM32F4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_def.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_exti.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_exti.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_i2c.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_i2c.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_i2c_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_spi.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_tim.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_tim_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_uart.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_usart.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pcd.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_hal_pcd_ex.h;Drivers\STM32F4xx_HAL_Driver\Inc\stm32f4xx_ll_usb.h;Drivers\CMSIS\Device\ST\STM32F4xx\Include\stm32f405xx.h;Drivers\CMSIS\Device\ST\STM32F4xx\Include\stm32f4xx.h;Drivers\CMSIS\Device\ST\STM32F4xx\Include\system_stm32f4xx.h;Drivers\CMSIS\Device\ST\STM32F4xx\Source\Templates\system_stm32f4xx.c;Drivers\CMSIS\Include\cmsis_armcc.h;Drivers\CMSIS\Include\cmsis_armclang.h;Drivers\CMSIS\Include\cmsis_compiler.h;Drivers\CMSIS\Include\cmsis_gcc.h;Drivers\CMSIS\Include\cmsis_iccarm.h;Drivers\CMSIS\Include\cmsis_version.h;Drivers\CMSIS\Include\core_armv8mbl.h;Drivers\CMSIS\Include\core_armv8mml.h;Drivers\CMSIS\Include\core_cm0.h;Drivers\CMSIS\Include\core_cm0plus.h;Drivers\CMSIS\Include\core_cm1.h;Drivers\CMSIS\Include\core_cm23.h;Drivers\CMSIS\Include\core_cm3.h;Drivers\CMSIS\Include\core_cm33.h;Drivers\CMSIS\Include\core_cm4.h;Drivers\CMSIS\Include\core_cm7.h;Drivers\CMSIS\Include\core_sc000.h;Drivers\CMSIS\Include\core_sc300.h;Drivers\CMSIS\Include\mpu_armv7.h;Drivers\CMSIS\Include\mpu_armv8.h;Drivers\CMSIS\Include\tz_context.h; - -[PreviousUsedMakefileFiles] -SourceFiles=Core\Src\main.c;Core\Src\stm32f4xx_it.c;Core\Src\stm32f4xx_hal_msp.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_can.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ramfunc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_gpio.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_cortex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_exti.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_spi.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_uart.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_ll_usb.c;Drivers\CMSIS\Device\ST\STM32F4xx\Source\Templates\system_stm32f4xx.c;Core\Src\system_stm32f4xx.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_can.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_rcc_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_flash_ramfunc.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_gpio.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_dma.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pwr_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_cortex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_exti.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_spi.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_tim_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_uart.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_pcd_ex.c;Drivers\STM32F4xx_HAL_Driver\Src\stm32f4xx_ll_usb.c;Drivers\CMSIS\Device\ST\STM32F4xx\Source\Templates\system_stm32f4xx.c;Core\Src\system_stm32f4xx.c;;; -HeaderPath=Drivers\STM32F4xx_HAL_Driver\Inc;Drivers\STM32F4xx_HAL_Driver\Inc\Legacy;Drivers\CMSIS\Device\ST\STM32F4xx\Include;Drivers\CMSIS\Include;Core\Inc; -CDefines=USE_HAL_DRIVER;STM32F405xx;USE_HAL_DRIVER;USE_HAL_DRIVER; - -[PreviousGenFiles] -AdvancedFolderStructure=true -HeaderFileListSize=3 -HeaderFiles#0=..\Core\Inc\stm32f4xx_it.h -HeaderFiles#1=..\Core\Inc\stm32f4xx_hal_conf.h -HeaderFiles#2=..\Core\Inc\main.h -HeaderFolderListSize=1 -HeaderPath#0=..\Core\Inc -HeaderFiles=; -SourceFileListSize=3 -SourceFiles#0=..\Core\Src\stm32f4xx_it.c -SourceFiles#1=..\Core\Src\stm32f4xx_hal_msp.c -SourceFiles#2=..\Core\Src\main.c -SourceFolderListSize=1 -SourcePath#0=..\Core\Src -SourceFiles=; - +[PreviousLibFiles] +LibFiles=Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dmamux.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dmamux.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f405xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/cmsis_armclang.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/cmsis_gcc.h; + +[PreviousUsedMakefileFiles] +SourceFiles=Core/Src/main.c;Core/Src/stm32f4xx_it.c;Core/Src/stm32f4xx_hal_msp.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Core/Src/system_stm32f4xx.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Core/Src/system_stm32f4xx.c;;; +HeaderPath=Drivers/STM32F4xx_HAL_Driver/Inc;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy;Drivers/CMSIS/Device/ST/STM32F4xx/Include;Drivers/CMSIS/Include;Core/Inc; +CDefines=USE_HAL_DRIVER;STM32F405xx;USE_HAL_DRIVER;USE_HAL_DRIVER; + +[PreviousGenFiles] +AdvancedFolderStructure=true +HeaderFileListSize=3 +HeaderFiles#0=../Core/Inc/stm32f4xx_it.h +HeaderFiles#1=../Core/Inc/stm32f4xx_hal_conf.h +HeaderFiles#2=../Core/Inc/main.h +HeaderFolderListSize=1 +HeaderPath#0=../Core/Inc +HeaderFiles=; +SourceFileListSize=3 +SourceFiles#0=../Core/Src/stm32f4xx_it.c +SourceFiles#1=../Core/Src/stm32f4xx_hal_msp.c +SourceFiles#2=../Core/Src/main.c +SourceFolderListSize=1 +SourcePath#0=../Core/Src +SourceFiles=; + diff --git a/Core/Inc/analyzer.h b/Core/Inc/analyzer.h index 702f040..74f5b70 100644 --- a/Core/Inc/analyzer.h +++ b/Core/Inc/analyzer.h @@ -5,6 +5,37 @@ #include "datastructs.h" #include "segment.h" +// this is a simple empirical mapping of which therms are returning good data +// Only in use because we can not seem to correclty map incoming therms - this allows us to forcibley select those that we visually noticed were good +extern uint8_t THERM_DISABLE[NUM_CHIPS][NUM_THERMS_PER_CHIP]; + +extern const uint8_t NO_THERM; +extern const uint8_t MUX_OFFSET; + +/** + * @brief Mapping the Relevant Thermistors for each cell based on cell # + * @note 0xFF indicates the end of the relevant therms + * @note Low side + */ +extern const uint8_t RELEVANT_THERM_MAP_L[NUM_CELLS_PER_CHIP][NUM_RELEVANT_THERMS]; + +/** + * @brief Mapping the Relevant Thermistors for each cell based on cell # + * @note 0xFF indicates the end of the relevant therms + * @note High side + */ +extern const uint8_t RELEVANT_THERM_MAP_H[NUM_CELLS_PER_CHIP][NUM_RELEVANT_THERMS]; + +/* + * List of therms that we actually read from, NOT reordered by cell + */ +extern const uint8_t POPULATED_THERM_LIST_L[NUM_THERMS_PER_CHIP]; + +/* + * List of therms that we actually read from, NOT reordered by cell + */ +extern const uint8_t POPULATED_THERM_LIST_H[NUM_THERMS_PER_CHIP]; + /* We want to make sure we aren't doing useless analysis on the same set of data since we are * backfilling segment data */ #define ANALYSIS_INTERVAL VOLTAGE_WAIT_TIME diff --git a/Core/Inc/bmsConfig.h b/Core/Inc/bmsConfig.h index 5cf69df..b2b036f 100644 --- a/Core/Inc/bmsConfig.h +++ b/Core/Inc/bmsConfig.h @@ -2,15 +2,15 @@ #define BMS_CONFIG_H // Hardware definition -#define NUM_SEGMENTS 4 -#define NUM_CHIPS NUM_SEGMENTS*2 -#define NUM_CELLS_PER_CHIP 9 +#define NUM_SEGMENTS 6 +#define NUM_CHIPS NUM_SEGMENTS* 2 +#define NUM_CELLS_PER_CHIP 10 #define NUM_THERMS_PER_CHIP 32 -#define NUM_RELEVANT_THERMS 5 +#define NUM_RELEVANT_THERMS 3 // Firmware limits #define MAX_TEMP 65 //degrees C -#define MIN_TEMP -15 // deg C +#define MIN_TEMP -25 // deg C #define MAX_VOLT_MEAS 65535 #define MIN_VOLT_MEAS 0 @@ -26,12 +26,15 @@ #define MAX_DELTA_V 0.015 #define BAL_MIN_V 4.00 #define MAX_CELL_TEMP 55 -#define MAX_CELL_CURR 700 // Amps per BMS cell +#define MIN_CELL_TEMP 15 +#define MAX_CELL_CURR 500 // Amps per BMS cell #define MAX_CELL_TEMP_BAL 45 -#define MAX_CHG_CELL_CURR 20 +#define MAX_CHG_CELL_CURR 20 // Algorithm settings -#define CHARGE_TIMEOUT 300000 // 5 minutes, may need adjustment +#define CHARGE_SETL_TIMEOUT 60000 // 1 minute, may need adjustment +#define CHARGE_SETL_TIMEUP 300000 // 5 minutes, may need adjustment +#define CHARGE_VOLT_TIMEOUT 300000 // 5 minutes, may need adjustment #define VOLT_SAG_MARGIN 0.45 // Volts above the minimum cell voltage we would like to aim for #define OCV_CURR_THRESH 1.5 @@ -40,18 +43,18 @@ #define MAX_STANDARD_DEV 3 // only used for standard deviation for therms calc //Fault times -#define OVER_CURR_TIME 1500 //todo adjust these based on testing and/or counter values +#define OVER_CURR_TIME 5000 //todo adjust these based on testing and/or counter values #define PRE_OVER_CURR_TIME 1000 #define OVER_CHG_CURR_TIME 1000 -#define UNDER_VOLT_TIME 15000 +#define UNDER_VOLT_TIME 45000 #define PRE_UNDER_VOLT_TIME 12000 -#define OVER_VOLT_TIME 15000 -#define LOW_CELL_TIME 15000 +#define OVER_VOLT_TIME 45000 +#define LOW_CELL_TIME 45000 #define HIGH_TEMP_TIME 60000 -#define CURR_ERR_MARG 50 // in A * 10 +#define CURR_ERR_MARG 1.1 // scaling factor, ie 1.1 = 10% error -#define DCDC_CURRENT_DRAW 2 // in A, this is generous +#define DCDC_CURRENT_DRAW 0 // in A, was used because our DCDC was drawing current -#define CAN_MESSAGE_WAIT 10 +#define CAN_MESSAGE_WAIT 5 #endif \ No newline at end of file diff --git a/Core/Inc/can_handler.h b/Core/Inc/can_handler.h index 559ea8e..6f9da20 100644 --- a/Core/Inc/can_handler.h +++ b/Core/Inc/can_handler.h @@ -4,6 +4,7 @@ #include "can.h" #include "stm32f4xx_hal.h" #include +#include "ringbuffer.h" #define NUM_INBOUND_CAN1_IDS 1 @@ -15,14 +16,14 @@ extern CAN_HandleTypeDef hcan2; extern ringbuffer_t* can1_rx_queue; extern ringbuffer_t* can2_rx_queue; -static const uint16_t can1_id_list[NUM_INBOUND_CAN1_IDS] = { +static const uint32_t can1_id_list[NUM_INBOUND_CAN1_IDS] = { //CANID_X, 0x0000 }; -static const uint16_t can2_id_list[NUM_INBOUND_CAN2_IDS] = { +static const uint32_t can2_id_list[NUM_INBOUND_CAN2_IDS] = { //CANID_X, - 0x0000 + 0x18FF50E5 }; diff --git a/Core/Inc/compute.h b/Core/Inc/compute.h index a9eaf25..611305e 100644 --- a/Core/Inc/compute.h +++ b/Core/Inc/compute.h @@ -13,12 +13,24 @@ #define CHARGE_DETECT 5 #define CHARGER_BAUD 250000U #define MC_BAUD 1000000U -#define MAX_ADC_RESOLUTION 1023 // 13 bit ADC +#define MAX_ADC_RESOLUTION 4095 // 12 bit ADC + + + +typedef enum { + FAN1, + FAN2, + FAN3, + FAN4, + FAN5, + FAN6, + FANMAX +} fan_select_t; /** * @brief inits the compute interface */ -void compute_init(); +uint8_t compute_init(); /** * @brief sets safeguard bool to check whether charging is enabled or disabled @@ -35,7 +47,7 @@ void compute_enable_charging(bool enable_charging); * * @return Returns a fault if we are not able to communicate with charger */ -int compute_send_charging_message(uint16_t voltage_to_set, acc_data_t* bms_data); +int compute_send_charging_message(uint16_t voltage_to_set, uint16_t current_to_set, acc_data_t* bms_data); /** * @brief Returns if charger interlock is engaged, indicating charger LV connector is plugged in @@ -56,10 +68,13 @@ bool compute_charger_connected(); /** * @brief Sets the desired fan speed - * - * @param new_fan_speed + * + * @param new_fan_speed + * @param fan_select + * + * @return uint8_t 0 = success, 1 = fan_select is out of range, 2 = PWM channel not able to be configured */ -void compute_set_fan_speed(uint8_t new_fan_speed); +uint8_t compute_set_fan_speed(TIM_HandleTypeDef* pwmhandle, fan_select_t fan_select, uint8_t duty_cycle); /** * @brief Returns the pack current sensor reading @@ -68,13 +83,19 @@ void compute_set_fan_speed(uint8_t new_fan_speed); */ int16_t compute_get_pack_current(); +/** + * @brief sends max discharge current to Motor Controller + * + * @param bmsdata + */ +void compute_send_mc_discharge_message(acc_data_t* bmsdata); + /** * @brief sends max charge/discharge current to Motor Controller * - * @param max_charge - * @param max_discharge + * @param bmsdata */ -void compute_send_mc_message(uint16_t max_charge, uint16_t max_discharge); +void compute_send_mc_charge_message(acc_data_t* bmsdata); /** * @brief updates fault relay @@ -168,4 +189,7 @@ void compute_send_cell_temp_message(acc_data_t* bmsdata); */ void compute_send_segment_temp_message(acc_data_t* bmsdata); +void compute_send_fault_message(uint8_t status, int16_t curr, int16_t in_dcl); +void compute_send_voltage_noise_message(acc_data_t* bmsdata); + #endif // COMPUTE_H diff --git a/Core/Inc/datastructs.h b/Core/Inc/datastructs.h index 5fb35d3..af344e8 100644 --- a/Core/Inc/datastructs.h +++ b/Core/Inc/datastructs.h @@ -12,7 +12,7 @@ */ typedef struct { /* These are retrieved from the initial LTC comms */ - uint16_t voltage_reading[NUM_CELLS_PER_CHIP]; /* store voltage readings from each chip */ + uint16_t voltage[NUM_CELLS_PER_CHIP]; /* store voltage readings from each chip */ int8_t thermistor_reading[NUM_THERMS_PER_CHIP]; /* store all therm readings from each chip */ int8_t thermistor_value[NUM_THERMS_PER_CHIP]; int error_reading; @@ -22,7 +22,8 @@ typedef struct { float cell_resistance[NUM_CELLS_PER_CHIP]; uint16_t open_cell_voltage[NUM_CELLS_PER_CHIP]; - uint8_t bad_volt_diff_count[NUM_CELLS_PER_CHIP]; + uint8_t noise_reading[NUM_CELLS_PER_CHIP]; /* bool representing noise ignored read */ + uint8_t consecutive_noise[NUM_CELLS_PER_CHIP]; /* count representing consecutive noisy reads */ } chipdata_t; /** @@ -36,8 +37,8 @@ typedef enum { /* Orion BMS faults */ CELLS_NOT_BALANCING = 0x1, - CELL_VOLTAGE_TOO_HIGH = 0x2, - CELL_VOLTAGE_TOO_LOW = 0x4, + CELL_VOLTAGE_TOO_HIGH = 0x4, + CELL_VOLTAGE_TOO_LOW = 0x2, PACK_TOO_HOT = 0x8, OPEN_WIRING_FAULT = 0x10, /* cell tap wire is either weakly connected or not connected */ INTERNAL_SOFTWARE_FAULT = 0x20, /* general software fault */ @@ -92,6 +93,7 @@ typedef struct { uint8_t soc; int8_t segment_average_temps[NUM_SEGMENTS]; + uint8_t segment_noise_percentage[NUM_SEGMENTS]; /** * @brief Note that this is a 32 bit integer, so there are 32 max possible fault codes diff --git a/Core/Inc/main.h b/Core/Inc/main.h index d20ed6b..3e0f39b 100644 --- a/Core/Inc/main.h +++ b/Core/Inc/main.h @@ -41,7 +41,6 @@ extern "C" { /* Exported constants --------------------------------------------------------*/ /* USER CODE BEGIN EC */ - /* USER CODE END EC */ /* Exported macro ------------------------------------------------------------*/ @@ -49,6 +48,8 @@ extern "C" { /* USER CODE END EM */ +void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); + /* Exported functions prototypes ---------------------------------------------*/ void Error_Handler(void); @@ -61,8 +62,6 @@ void Error_Handler(void); #define FPGA_Reset_GPIO_Port GPIOC #define Communication_GPIO_Pin GPIO_PIN_14 #define Communication_GPIO_GPIO_Port GPIOC -#define Communication_GPIOC15_Pin GPIO_PIN_15 -#define Communication_GPIOC15_GPIO_Port GPIOC #define Communication_GPIOC0_Pin GPIO_PIN_0 #define Communication_GPIOC0_GPIO_Port GPIOC #define SPI_2_CS_Pin GPIO_PIN_1 @@ -79,8 +78,6 @@ void Error_Handler(void); #define I_Sense_GPIO_Port GPIOC #define I_SenseB0_Pin GPIO_PIN_0 #define I_SenseB0_GPIO_Port GPIOB -#define I_SenseB1_Pin GPIO_PIN_1 -#define I_SenseB1_GPIO_Port GPIOB #define I_SenseB2_Pin GPIO_PIN_2 #define I_SenseB2_GPIO_Port GPIOB #define Debug_LEDB11_Pin GPIO_PIN_11 diff --git a/Core/Inc/stateMachine.h b/Core/Inc/stateMachine.h index 3b2d550..c442837 100644 --- a/Core/Inc/stateMachine.h +++ b/Core/Inc/stateMachine.h @@ -64,4 +64,13 @@ void sm_handle_state(acc_data_t *bmsdata); void sm_balance_cells(acc_data_t *bms_data); void sm_broadcast_current_limit(acc_data_t *bmsdata); +/** + * @brief algorithm to calculate and set fan speed based on temperature + * + * @param bmsdata + * +*/ +void calculate_pwm(acc_data_t *bmsdata); + + #endif //BMS_STATES_H \ No newline at end of file diff --git a/Core/Inc/stm32f4xx_hal_conf.h b/Core/Inc/stm32f4xx_hal_conf.h index ddcd734..e28f8b1 100644 --- a/Core/Inc/stm32f4xx_hal_conf.h +++ b/Core/Inc/stm32f4xx_hal_conf.h @@ -38,7 +38,7 @@ #define HAL_MODULE_ENABLED /* #define HAL_CRYP_MODULE_ENABLED */ -/* #define HAL_ADC_MODULE_ENABLED */ +#define HAL_ADC_MODULE_ENABLED #define HAL_CAN_MODULE_ENABLED /* #define HAL_CRC_MODULE_ENABLED */ /* #define HAL_CAN_LEGACY_MODULE_ENABLED */ @@ -55,7 +55,7 @@ /* #define HAL_HASH_MODULE_ENABLED */ #define HAL_I2C_MODULE_ENABLED /* #define HAL_I2S_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ +#define HAL_IWDG_MODULE_ENABLED /* #define HAL_LTDC_MODULE_ENABLED */ /* #define HAL_RNG_MODULE_ENABLED */ /* #define HAL_RTC_MODULE_ENABLED */ @@ -63,7 +63,7 @@ /* #define HAL_SD_MODULE_ENABLED */ /* #define HAL_MMC_MODULE_ENABLED */ #define HAL_SPI_MODULE_ENABLED -/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_TIM_MODULE_ENABLED #define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_IRDA_MODULE_ENABLED */ diff --git a/Core/Inc/stm32f4xx_it.h b/Core/Inc/stm32f4xx_it.h index 0f1d5fe..7c70832 100644 --- a/Core/Inc/stm32f4xx_it.h +++ b/Core/Inc/stm32f4xx_it.h @@ -55,6 +55,9 @@ void SVC_Handler(void); void DebugMon_Handler(void); void PendSV_Handler(void); void SysTick_Handler(void); +void DMA2_Stream0_IRQHandler(void); +void CAN2_RX0_IRQHandler(void); +void CAN2_RX1_IRQHandler(void); /* USER CODE BEGIN EFP */ /* USER CODE END EFP */ diff --git a/Core/Src/analyzer.c b/Core/Src/analyzer.c index 183803b..b495a5b 100644 --- a/Core/Src/analyzer.c +++ b/Core/Src/analyzer.c @@ -1,5 +1,6 @@ #include "analyzer.h" #include +#include acc_data_t* bmsdata; @@ -17,8 +18,8 @@ acc_data_t* prevbmsdata; */ const float TEMP_TO_CELL_RES[14] = { - 5.52, 4.84, 4.27, 3.68, 3.16, 2.74, 2.4, - 2.12, 1.98, 1.92, 1.90, 1.90, 1.90, 1.90 + 5.52 * (7/5), 4.84 * (7/5), 4.27 * (7/5), 3.68 * (7/5), 3.16 * (7/5), 2.74 * (7/5), 2.4 * (7/5), + 2.12 * (7/5), 1.98 * (7/5), 1.92 * (7/5), 1.90 * (7/5), 1.90 * (7/5), 1.90 * (7/5), 1.90 * (7/5) }; /** @@ -66,23 +67,6 @@ const uint8_t STATE_OF_CHARGE_CURVE[18] = 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 15, 24, 56, 74, 85, 95, 98, 100 }; -/** - * @brief Mapping the Relevant Thermistors for each cell based on cell # - * @note 0xFF indicates the end of the relevant therms - */ -const uint8_t RelevantThermMap[NUM_CELLS_PER_CHIP][NUM_RELEVANT_THERMS] = -{ - {17, 18, 0xFF, 0xFF, 0xFF}, - {17, 18, 0xFF, 0xFF, 0xFF}, - {17, 18, 19, 20, 0xFF}, - {19, 20, 0xFF, 0xFF, 0xFF}, - {19, 20, 21, 22, 23}, - {21, 22, 23, 24, 25}, - {24, 25, 0xFF, 0xFF, 0xFF}, - {24, 25, 26, 27, 0xFF}, - {26, 27, 0xFF, 0xFF, 0xFF} -}; - /** * @brief Mapping desired fan speed PWM to the cell temperature * @@ -96,22 +80,100 @@ const uint8_t FAN_CURVE[16] = 128, 255, 255, 255, 255, 255 }; +const uint8_t NO_THERM = 0xFF; +const uint8_t MUX_OFFSET = 16; + +/** + * @brief Mapping the Relevant Thermistors for each cell based on cell # + * @note 0xFF indicates the end of the relevant therms + * @note High side + */ +const uint8_t RELEVANT_THERM_MAP_H[NUM_CELLS_PER_CHIP][NUM_RELEVANT_THERMS] = +{ + {5, 3, NO_THERM}, + {12 + MUX_OFFSET, 14 + MUX_OFFSET, NO_THERM}, + {2, 0, 1}, + {9 + MUX_OFFSET, 11 + MUX_OFFSET, NO_THERM}, + {8, 6, NO_THERM}, + {0 + MUX_OFFSET, 2 + MUX_OFFSET, NO_THERM}, + {12, 14, 13}, + {3 + MUX_OFFSET, 5 + MUX_OFFSET, NO_THERM}, + {11, 9, NO_THERM}, + {6 + MUX_OFFSET, 8 + MUX_OFFSET, NO_THERM}, +}; + +/** + * @brief Mapping the Relevant Thermistors for each cell based on cell # + * @note 0xFF indicates the end of the relevant therms + * @note Low side + */ +const uint8_t RELEVANT_THERM_MAP_L[NUM_CELLS_PER_CHIP][NUM_RELEVANT_THERMS] = +{ + {5, 3, 4}, + {12 + MUX_OFFSET, 14 + MUX_OFFSET, NO_THERM}, + {2, 0, NO_THERM}, + {11 + MUX_OFFSET, 9 + MUX_OFFSET, NO_THERM}, + {6, 7, 8}, + {0 + MUX_OFFSET, 2 + MUX_OFFSET, NO_THERM}, + {14, 12, NO_THERM}, + {5 + MUX_OFFSET, 3 + MUX_OFFSET, NO_THERM}, + {9, 10, 11}, + {6 + MUX_OFFSET, 8 + MUX_OFFSET, NO_THERM}, +}; + +uint8_t THERM_DISABLE[NUM_CHIPS][NUM_THERMS_PER_CHIP] = +{ + {1,0,1,0,0,1,0,1,1,1,0,1,0,0,1,0,0,0,1,0,0,0,0,1,1,1,0,0,0,0,1,0 }, + {1,0,1,0,0,1,0,0,1,0,1,1,0,1,1,0,0,1,1,1,0,1,0,1,1,1,1,1,0,1,1,1 }, + {1,0,1,0,0,1,0,0,1,0,0,1,1,0,1,0,0,0,1,0,0,0,1,0,0,0,1,0,0,0,1,0 }, + {1,0,1,0,0,1,0,0,1,1,0,1,0,0,1,0,0,0,0,0,1,1,1,0,1,0,0,1,0,0,0,0 }, + {1,0,1,0,0,1,0,1,1,0,0,1,0,0,1,0,1,0,1,0,0,0,0,0,0,0,0,0,0,1,1,1 }, + {1,0,1,0,0,1,0,0,1,0,0,1,0,0,1,0,0,0,0,0,0,1,0,0,1,0,1,1,1,0,0,0 }, + {1,0,1,0,0,1,0,0,1,0,1,1,0,0,1,1,0,0,1,0,1,1,1,0,0,0,0,0,0,0,1,0 }, + {1,0,1,0,0,1,0,0,1,0,0,1,0,0,1,0,0,0,0,0,0,1,0,0,1,0,1,1,1,1,1,1 }, + {1,1,1,0,0,1,0,0,1,0,0,1,0,0,1,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,1,0 }, + {1,0,1,0,0,0,0,0,1,0,0,1,0,0,1,0,1,0,0,1,0,1,0,0,1,0,0,1,0,0,0,0 }, + {1,1,1,0,0,1,0,0,1,1,0,1,0,0,1,0,0,1,1,0,0,0,0,0,0,0,0,0,0,0,1,0 }, + {1,1,1,0,0,1,0,1,1,0,0,1,1,0,1,0,0,0,0,0,0,1,0,1,1,1,0,1,0,1,0,0 } +}; + +/* + * List of therms that we actually read from, NOT reordered by cell + */ +const uint8_t POPULATED_THERM_LIST_H[NUM_THERMS_PER_CHIP] = +{ + true, false, true, + true, true, true, + true, true, true, + true, true, true, + true, false, true, false, + true, false, true, + true, false, true, + true, false, true, + true, false, true, + true, false, true, false +}; + +const uint8_t POPULATED_THERM_LIST_L[NUM_THERMS_PER_CHIP] = +{ + true, true, true, + true, false, true, + true, false, true, + true, false, true, + true, true, true, false, + true, false, true, + true, false, true, + true, false, true, + true, false, true, + true, false, true, false +}; + /** * @brief Selecting thermistors to ignore * * @note True / 1 will disable the thermistor + * @note disabling both unpopulaed (see above) and populated but bad cells ( not great permanent solution) */ -const uint8_t THERM_DISABLE[8][11] = -{ - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0}, - {0,0,0,0,0,0,0,0,0,0,0} -}; // clang-format on @@ -126,65 +188,95 @@ void high_curr_therm_check(); void diff_curr_therm_check(); void calc_state_of_charge(); +/* we are not corrctly mapping each therm reading to the correct cell. So, we are taking the average of all good readings (not disabled) for a given chip, + and assigning that to be the cell val for every cell in the chip*/ + void calc_cell_temps() { for (uint8_t c = 0; c < NUM_CHIPS; c++) { for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { + const uint8_t (*therm_map)[NUM_RELEVANT_THERMS] = (c % 2 == 0) ? RELEVANT_THERM_MAP_L : RELEVANT_THERM_MAP_H; + uint8_t therm_count = 0; int temp_sum = 0; for (uint8_t therm = 0; therm < NUM_RELEVANT_THERMS; therm++) { - uint8_t thermNum = RelevantThermMap[cell][therm]; - temp_sum += bmsdata->chip_data[c].thermistor_value[thermNum]; - } - - /* Takes the average temperature of all the relevant thermistors */ - bmsdata->chip_data[c].cell_temp[cell] = temp_sum / NUM_RELEVANT_THERMS; + uint8_t thermNum = therm_map[cell][therm]; - /* Cleansing value */ - if (bmsdata->chip_data[c].cell_temp[cell] > MAX_TEMP) { - bmsdata->chip_data[c].cell_temp[cell] = MAX_TEMP; + if (thermNum != NO_THERM) { + //printf("%d\t", bmsdata->chip_data[c].thermistor_value[therm]); + temp_sum += bmsdata->chip_data[c].thermistor_value[therm]; + therm_count++; + } } + //printf("\r\n"); + /* Takes the average temperature of all the relevant thermistors */ + bmsdata->chip_data[c].cell_temp[cell] = temp_sum / therm_count; + therm_count = 0; } } } void calc_pack_temps() { - bmsdata->max_temp.val = MIN_TEMP; + bmsdata->max_temp.val = MIN_TEMP; bmsdata->max_temp.cellNum = 0; - bmsdata->max_temp.chipIndex = 0; + bmsdata->max_temp.chipIndex = 0; - bmsdata->min_temp.val = MAX_TEMP; + bmsdata->min_temp.val = MAX_TEMP; bmsdata->min_temp.cellNum = 0; - bmsdata->min_temp.chipIndex = 0; + bmsdata->min_temp.chipIndex = 0; int total_temp = 0; int total_seg_temp = 0; + int total_accepted = 0; for (uint8_t c = 0; c < NUM_CHIPS; c++) { - for (uint8_t therm = 17; therm < 28; therm++) { + for (uint8_t therm = 0; therm < NUM_THERMS_PER_CHIP; therm++) { /* finds out the maximum cell temp and location */ - if (bmsdata->chip_data[c].thermistor_value[therm] > bmsdata->max_temp.val) { - bmsdata->max_temp.val = bmsdata->chip_data[c].thermistor_value[therm]; - bmsdata->max_temp.cellNum = c; - bmsdata->max_temp.chipIndex = therm; - } + + //if (THERM_DISABLE[c][therm]) continue; + total_accepted++; + //if (bmsdata->chip_data[c].thermistor_value[therm] > bmsdata->max_temp.val) { + // bmsdata->max_temp.val = bmsdata->chip_data[c].thermistor_value[therm]; + // bmsdata->max_temp.cellNum = c; + // bmsdata->max_temp.chipIndex = therm; + //} /* finds out the minimum cell temp and location */ - if (bmsdata->chip_data[c].thermistor_value[therm] < bmsdata->min_temp.val) { - bmsdata->min_temp.val = bmsdata->chip_data[c].thermistor_value[therm]; - bmsdata->min_temp.cellNum = c; - bmsdata->min_temp.chipIndex = therm; - } + //if (bmsdata->chip_data[c].thermistor_value[therm] < bmsdata->min_temp.val) { + // bmsdata->min_temp.val = bmsdata->chip_data[c].thermistor_value[therm]; + // bmsdata->min_temp.cellNum = c; + // bmsdata->min_temp.chipIndex = therm; + //} total_temp += bmsdata->chip_data[c].thermistor_value[therm]; total_seg_temp += bmsdata->chip_data[c].thermistor_value[therm]; } + + /* only for NERO */ if (c % 2 == 0) { bmsdata->segment_average_temps[c / 2] = total_seg_temp / 22; total_seg_temp = 0; } } + + for (uint8_t c = 0; c < NUM_CHIPS; c++) { + for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { + if (bmsdata->chip_data[c].cell_temp[cell] > bmsdata->max_temp.val) { + bmsdata->max_temp.val = bmsdata->chip_data[c].cell_temp[cell]; + bmsdata->max_temp.cellNum = cell; + bmsdata->max_temp.chipIndex = c; + } + + /* finds out the minimum cell temp and location */ + if (bmsdata->chip_data[c].cell_temp[cell] < bmsdata->min_temp.val) { + bmsdata->min_temp.val = bmsdata->chip_data[c].cell_temp[cell]; + bmsdata->min_temp.cellNum = cell; + bmsdata->min_temp.chipIndex = c; + } + } + } + /* takes the average of all the cell temperatures */ - bmsdata->avg_temp = total_temp / 88; + bmsdata->avg_temp = total_temp / (total_accepted); } void calc_pack_voltage_stats() @@ -212,8 +304,8 @@ void calc_pack_voltage_stats() for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { /* fings out the maximum cell voltage and location */ - if (bmsdata->chip_data[c].voltage_reading[cell] > bmsdata->max_voltage.val) { - bmsdata->max_voltage.val = bmsdata->chip_data[c].voltage_reading[cell]; + if (bmsdata->chip_data[c].voltage[cell] > bmsdata->max_voltage.val) { + bmsdata->max_voltage.val = bmsdata->chip_data[c].voltage[cell]; bmsdata->max_voltage.chipIndex = c; bmsdata->max_voltage.cellNum = cell; } @@ -225,8 +317,8 @@ void calc_pack_voltage_stats() } /* finds out the minimum cell voltage and location */ - if (bmsdata->chip_data[c].voltage_reading[cell] < bmsdata->min_voltage.val) { - bmsdata->min_voltage.val = bmsdata->chip_data[c].voltage_reading[cell]; + if (bmsdata->chip_data[c].voltage[cell] < bmsdata->min_voltage.val) { + bmsdata->min_voltage.val = bmsdata->chip_data[c].voltage[cell]; bmsdata->min_voltage.chipIndex = c; bmsdata->min_voltage.cellNum = cell; } @@ -237,7 +329,7 @@ void calc_pack_voltage_stats() bmsdata->min_ocv.cellNum = cell; } - total_volt += bmsdata->chip_data[c].voltage_reading[cell]; + total_volt += bmsdata->chip_data[c].voltage[cell]; total_ocv += bmsdata->chip_data[c].open_cell_voltage[cell]; } } @@ -277,7 +369,7 @@ void calc_cell_resistances() void calc_dcl() { - nertimer_t dcl_timer; + static nertimer_t dcl_timer; int16_t current_limit = 0x7FFF; @@ -295,12 +387,18 @@ void calc_dcl() current_limit = tmpDCL; } } - + /* ceiling for current limit */ if (current_limit > MAX_CELL_CURR) { bmsdata->discharge_limit = MAX_CELL_CURR; } + /* protection against being init to a high value */ + if (bmsdata->discharge_limit > MAX_CELL_CURR) { + bmsdata->discharge_limit = 0; + } + + /* State machine to prevent DCL from plummeting, copy over last DCL for 500ms */ else if (!is_timer_active(&dcl_timer) && current_limit < 5) { if (prevbmsdata == NULL) { bmsdata->discharge_limit = current_limit; @@ -311,24 +409,32 @@ void calc_dcl() start_timer(&dcl_timer, 500); } - else if (is_timer_active(&dcl_timer)) { - if (is_timer_expired(&dcl_timer)) { + else if (is_timer_active(&dcl_timer)) + { + if (is_timer_expired(&dcl_timer)) + { bmsdata->discharge_limit = current_limit; } - if (current_limit > 5) { + if (current_limit > 5) + { bmsdata->discharge_limit = current_limit; cancel_timer(&dcl_timer); } - else { + else + { bmsdata->discharge_limit = prevbmsdata->discharge_limit; } - } else { + } + else + { bmsdata->discharge_limit = current_limit; } if (bmsdata->discharge_limit > DCDC_CURRENT_DRAW) + { bmsdata->discharge_limit -= DCDC_CURRENT_DRAW; + } } void calc_cont_dcl() @@ -383,6 +489,10 @@ void calc_cont_ccl() } else { bmsdata->cont_CCL = TEMP_TO_CCL[max_res_index]; } + + if (bmsdata->cont_CCL > MAX_CHG_CELL_CURR){ + bmsdata->cont_CCL = MAX_CHG_CELL_CURR; + } } void calc_open_cell_voltage() @@ -392,7 +502,7 @@ void calc_open_cell_voltage() for (uint8_t chip = 0; chip < NUM_CHIPS; chip++) { for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { bmsdata->chip_data[chip].open_cell_voltage[cell] - = bmsdata->chip_data[chip].voltage_reading[cell]; + = bmsdata->chip_data[chip].voltage[cell]; } } return; @@ -405,12 +515,12 @@ void calc_open_cell_voltage() for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { /* Sets open cell voltage to a moving average of OCV_AVG values */ bmsdata->chip_data[chip].open_cell_voltage[cell] - = ((uint32_t)(bmsdata->chip_data[chip].voltage_reading[cell]) + = ((uint32_t)(bmsdata->chip_data[chip].voltage[cell]) + ((uint32_t)(prevbmsdata->chip_data[chip].open_cell_voltage[cell]) * (OCV_AVG - 1))) / OCV_AVG; bmsdata->chip_data[chip].open_cell_voltage[cell] - = bmsdata->chip_data[chip].voltage_reading[cell]; + = bmsdata->chip_data[chip].voltage[cell]; if (bmsdata->chip_data[chip].open_cell_voltage[cell] > MAX_VOLT * 10000) { bmsdata->chip_data[chip].open_cell_voltage[cell] @@ -462,7 +572,7 @@ void analyzer_push(acc_data_t* data) disable_therms(); - high_curr_therm_check(); /* = prev if curr > 50 */ + //high_curr_therm_check(); /* = prev if curr > 50 */ // diff_curr_therm_check(); /* = prev if curr - prevcurr > 10 */ // variance_therm_check(); /* = prev if val > 5 deg difference */ // standard_dev_therm_check(); /* = prev if std dev > 3 */ @@ -475,25 +585,30 @@ void analyzer_push(acc_data_t* data) calc_cell_resistances(); calc_dcl(); calc_cont_dcl(); + //calcCCL(); calc_cont_ccl(); calc_state_of_charge(); + calc_noise_volt_percent(); + + data->charge_limit = data->cont_CCL; is_first_reading_ = false; } void disable_therms() { - int8_t temp_rep_1 = 25; /* Iniitalize to room temp (necessary to stabilize when the BMS first - boots up/has null values) */ - // if (!is_first_reading_) temp_rep_1 = prevbmsdata->avg_temp; /* Set to actual average temp of - // the pack */ + int8_t tmp_temp = 25; /* Iniitalize to room temp (necessary to stabilize when the BMS first boots up/has null values) */ + if (!is_first_reading_) tmp_temp = prevbmsdata->avg_temp; /* Set to actual average temp of the pack */ for (uint8_t c = 0; c < NUM_CHIPS; c++) { - for (uint8_t therm = 17; therm < 28; therm++) { + for (uint8_t therm = 0; therm < NUM_THERMS_PER_CHIP; therm++) { /* If 2D LUT shows therm should be disable */ - if (THERM_DISABLE[(c - 1) / 2][therm - 17]) { + if (THERM_DISABLE[c][therm]) { /* Nullify thermistor by setting to pack average */ - bmsdata->chip_data[c].thermistor_value[therm] = temp_rep_1; + bmsdata->chip_data[c].thermistor_value[therm] = tmp_temp; + } + else { + bmsdata->chip_data[c].thermistor_value[therm] = bmsdata->chip_data[c].thermistor_reading[therm]; } } } @@ -523,6 +638,26 @@ void calc_state_of_charge() } } +void calc_noise_volt_percent() +{ + int i = 0; + for (uint8_t seg = 0; seg < NUM_SEGMENTS; seg++) { + uint8_t count = 0; + /* merge results from each of the two chips ona given segment */ + for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { + count = bmsdata->chip_data[seg + i].noise_reading[cell]; + count += bmsdata->chip_data[seg + i + 1].noise_reading[cell]; + } + i++; + + /* turn into percentage */ + //printf("count: %d\r\n", count); + bmsdata->segment_noise_percentage[seg] = (uint8_t)(100 * (count) / (NUM_CELLS_PER_CHIP * 2.0f)); + + } +} + + void high_curr_therm_check() { if (prevbmsdata == NULL) diff --git a/Core/Src/can_handler.c b/Core/Src/can_handler.c index 0651343..35e290b 100644 --- a/Core/Src/can_handler.c +++ b/Core/Src/can_handler.c @@ -17,7 +17,8 @@ void can_receive_callback(CAN_HandleTypeDef* hcan) } new_msg.len = rx_header.DLC; - new_msg.id = rx_header.StdId; + // TODO: Make receiving compatible with standard IDs + new_msg.id = rx_header.ExtId; if (hcan == &hcan1) { ringbuffer_enqueue(can1_rx_queue, &new_msg); } else { @@ -45,22 +46,20 @@ int8_t get_can1_msg() int8_t get_can2_msg() { + /* no messages to read */ - if (ringbuffer_is_empty(can2_rx_queue)) + if (ringbuffer_is_empty(can2_rx_queue)) { return -1; - + } can_msg_t msg; ringbuffer_dequeue(can2_rx_queue, &msg); // TODO list : // 1. Charger connection flag - have Charger set up with following logic, add correct CAN ID switch (msg.id) { - case 0x00: - if (msg.data[0] == 0x01) { - bmsdata->is_charger_connected = true; - } else { - bmsdata->is_charger_connected = false; - } + /* CAN ID of message charger sends every second. */ + case 0x18FF50E5: + bmsdata->is_charger_connected = true; break; default: break; diff --git a/Core/Src/compute.c b/Core/Src/compute.c index 2112b25..9511632 100644 --- a/Core/Src/compute.c +++ b/Core/Src/compute.c @@ -1,12 +1,21 @@ #include "compute.h" #include "can_handler.h" #include "can.h" +#include "c_utils.h" #include "main.h" +#include +#include "stm32f405xx.h" #include +#include #define MAX_CAN1_STORAGE 10 #define MAX_CAN2_STORAGE 10 +#define REF_CHANNEL 0 +#define VOUT_CHANNEL 1 + +//#define CHARGING_ENABLED + uint8_t fan_speed; bool is_charging_enabled; enum { CHARGE_ENABLED, CHARGE_DISABLED }; @@ -14,27 +23,63 @@ enum { CHARGE_ENABLED, CHARGE_DISABLED }; extern CAN_HandleTypeDef hcan1; extern CAN_HandleTypeDef hcan2; +extern TIM_HandleTypeDef htim1; +extern TIM_HandleTypeDef htim8; + +extern ADC_HandleTypeDef hadc1; +extern ADC_HandleTypeDef hadc2; + +TIM_OC_InitTypeDef pwm_config; +ADC_ChannelConfTypeDef adc_config; + +const uint32_t fan_channels[6] = {TIM_CHANNEL_3, TIM_CHANNEL_1, TIM_CHANNEL_4, TIM_CHANNEL_3, TIM_CHANNEL_2, TIM_CHANNEL_1}; + can_t can1; // main can bus, used by most peripherals can_t can2; // p2p can bus with charger +uint32_t adc_values[2] = {0}; + /* private function defintions */ -uint8_t calc_charger_led_state(); +float read_ref_voltage(); +float read_vout(); -void compute_init() +uint8_t compute_init() { + // TODO throw all of these objects into a compute struct can1.hcan = &hcan1; can1.id_list = can1_id_list; can1.id_list_len = sizeof(can1_id_list) / sizeof(can1_id_list[0]); - can1.callback = can_receive_callback; + //can1.callback = can_receive_callback; can1_rx_queue = ringbuffer_create(MAX_CAN1_STORAGE, sizeof(can_msg_t)); can_init(&can1); can2.hcan = &hcan2; can2.id_list = can2_id_list; can2.id_list_len = sizeof(can2_id_list) / sizeof(can2_id_list[0]); - can2.callback = can_receive_callback; + //can2.callback = can_receive_callback; can2_rx_queue = ringbuffer_create(MAX_CAN2_STORAGE, sizeof(can_msg_t)); can_init(&can2); + + pwm_config.OCMode = TIM_OCMODE_PWM1; + pwm_config.Pulse = 0; + pwm_config.OCPolarity = TIM_OCPOLARITY_HIGH; + pwm_config.OCFastMode = TIM_OCFAST_DISABLE; + + if (HAL_TIM_PWM_ConfigChannel(&htim1, &pwm_config, fan_channels[FAN1]) != HAL_OK) return -1; + if (HAL_TIM_PWM_ConfigChannel(&htim8, &pwm_config, fan_channels[FAN2]) != HAL_OK) return -1; + + // HAL_TIM_PWM_Start(&htim1, fan_channels[FAN1]); + // HAL_TIM_PWM_Start(&htim1, fan_channels[FAN2]); + // HAL_TIM_PWM_Start(&htim8, fan_channels[FAN3]); + // HAL_TIM_PWM_Start(&htim8, fan_channels[FAN4]); + // HAL_TIM_PWM_Start(&htim8, fan_channels[FAN5]); + // HAL_TIM_PWM_Start(&htim8, fan_channels[FAN6]); + bmsdata->is_charger_connected = false; + + HAL_ADC_Start(&hadc2); + + return 0; + } void compute_enable_charging(bool enable_charging) @@ -42,46 +87,46 @@ void compute_enable_charging(bool enable_charging) is_charging_enabled = enable_charging; } -int compute_send_charging_message(uint16_t voltage_to_set, acc_data_t* bms_data) +int compute_send_charging_message(uint16_t voltage_to_set, uint16_t current_to_set, acc_data_t* bms_data) { - struct __attribute__((packed)) { - uint8_t charger_control; + struct __attribute__((__packed__)){ uint16_t charger_voltage; // Note the charger voltage sent over should be 10*desired voltage uint16_t charger_current; // Note the charge current sent over should be 10*desired current - // + 3200 - uint8_t charger_leds; - uint16_t reserved2_3; + uint8_t charger_control; + uint8_t reserved_1; + uint16_t reserved_23; } charger_msg_data; - uint16_t current_to_set = bms_data->charge_limit; - - if (!is_charging_enabled) { - charger_msg_data.charger_control = 0b101; - - can_msg_t charger_msg; - charger_msg.id = 0x00; // TODO replace with correct ID; - charger_msg.len = sizeof(charger_msg_data); - memcpy(charger_msg.data, &charger_msg_data, sizeof(charger_msg_data)); + charger_msg_data.charger_voltage = voltage_to_set * 10; + charger_msg_data.charger_current = current_to_set * 10; - can_send_msg(&can2, &charger_msg); + if (is_charging_enabled) { + charger_msg_data.charger_control = 0x00; //0:Start charging. + } else { + charger_msg_data.charger_control = 0xFF; // 1:battery protection, stop charging + } - } - - // equations taken from TSM2500 CAN protocol datasheet - charger_msg_data.charger_control = 0xFC; - charger_msg_data.charger_voltage = voltage_to_set * 10; - if (current_to_set > 10) { - current_to_set = 10; - } - charger_msg_data.charger_current = current_to_set * 10 + 3200; - charger_msg_data.charger_leds = calc_charger_led_state(bms_data); - charger_msg_data.reserved2_3 = 0xFFFF; + charger_msg_data.reserved_1 = 0x00; + charger_msg_data.reserved_23 = 0x0000; can_msg_t charger_msg; - charger_msg.id = 0x00; // TODO replace with correct ID; + charger_msg.id = 0x1806E5F4; charger_msg.len = 8; memcpy(charger_msg.data, &charger_msg_data, sizeof(charger_msg_data)); - can_send_msg(&can2, &charger_msg); + + uint8_t temp = charger_msg.data[0]; + charger_msg.data[0] = charger_msg.data[1]; + charger_msg.data[1] = temp; + temp = charger_msg.data[2]; + charger_msg.data[2] = charger_msg.data[3]; + charger_msg.data[3] = temp; + + #ifdef CHARGING_ENABLED + HAL_StatusTypeDef res = can_send_extended_msg(&can2, &charger_msg); + if(res != HAL_OK) { + printf("CAN ERROR CODE %X", res); + } + #endif return 0; } @@ -89,7 +134,7 @@ int compute_send_charging_message(uint16_t voltage_to_set, acc_data_t* bms_data) bool compute_charger_connected() { //TODO need to set up CAN msg that actually toggles this bool - return bmsdata->is_charger_connected; + return false; //bmsdata->is_charger_connected; } //TODO add this back @@ -98,10 +143,19 @@ bool compute_charger_connected() // return; // } -void compute_set_fan_speed(uint8_t new_fan_speed) +uint8_t compute_set_fan_speed(TIM_HandleTypeDef* pwmhandle, fan_select_t fan_select, uint8_t duty_cycle) { - fan_speed = new_fan_speed; - // NERduino.setAMCDutyCycle(new_fan_speed); Replace + if (!pwmhandle) return -1; + if (fan_select >= FANMAX) return -1; + if (duty_cycle > 100) return -1; + + uint32_t CCR_value = 0; + uint32_t channel = fan_channels[fan_select]; + + CCR_value = (pwmhandle->Instance->ARR * duty_cycle) / 100; + __HAL_TIM_SET_COMPARE(pwmhandle, channel, CCR_value); + + return 0; } void compute_set_fault(int fault_state) @@ -113,64 +167,116 @@ void compute_set_fault(int fault_state) int16_t compute_get_pack_current() { - static const float CURRENT_LOWCHANNEL_MAX = 75.0; // Amps - static const float CURRENT_LOWCHANNEL_MIN = -75.0; // Amps - // static const float CURRENT_SUPPLY_VOLTAGE = 5.038; - static const float CURRENT_ADC_RESOLUTION = 5.0 / MAX_ADC_RESOLUTION; - - static const float CURRENT_LOWCHANNEL_OFFSET = 2.517; // Calibrated with current = 0A - static const float CURRENT_HIGHCHANNEL_OFFSET = 2.520; // Calibrated with current = 0A - - static const float HIGHCHANNEL_GAIN = 1 / 0.004; // Calibrated with current = 5A, 10A, 20A - static const float LOWCHANNEL_GAIN = 1 / 0.0267; - - static const float REF5V_DIV = 19.02 / (19.08 + 19.02); // Resistive divider in kOhm - static const float REF5V_CONV = 1 / REF5V_DIV; // Converting from reading to real value - - //TODO ADD BACK THE COMMENTED OUT ANALOG READS - float ref_5V = /*analogRead(MEAS_5VREF_PIN) * */(3.3 / MAX_ADC_RESOLUTION) * REF5V_CONV; - int16_t high_current - = 10 - /* * (((5 / ref_5V) * /analogRead(CURRENT_SENSOR_PIN_L) * CURRENT_ADC_RESOLUTION)) - - CURRENT_HIGHCHANNEL_OFFSET) */ - * HIGHCHANNEL_GAIN; // Channel has a large range with low resolution - int16_t low_current - = 10 - /* * (((5 / ref_5V) * (analogRead(CURRENT_SENSOR_PIN_H) * CURRENT_ADC_RESOLUTION)) - - CURRENT_LOWCHANNEL_OFFSET) */ - * LOWCHANNEL_GAIN; // Channel has a small range with high resolution - - // Serial.print("High: "); - // Serial.println(-high_current); - // Serial.print("Low: "); - // Serial.println(-low_current); - // Serial.print("5V: "); - // Serial.println(ref_5V); - - // If the current is scoped within the range of the low channel, use the low channel - if (low_current < CURRENT_LOWCHANNEL_MAX - 5.0 || low_current > CURRENT_LOWCHANNEL_MIN + 5.0) { - return -low_current; - } + // static const float GAIN = 5.00; // mV/A + // static const float OFFSET = 0.0; // mV + // static const uint8_t num_samples = 10; + // static int16_t current_accumulator = 0.0; // A + + // /* starting equation : Vout = Vref + Voffset + (Gain * Ip) */ + // float ref_voltage = read_ref_voltage(); + // float vout = read_vout(); + + // ref_voltage *= 1000;// convert to mV + // vout *= 1000; + + // int16_t current = (vout - ref_voltage - OFFSET) / (GAIN); // convert to V + + // /* Low Pass Filter of Current*/ + // current = ((current_accumulator * (num_samples - 1)) + current) / num_samples; + // current_accumulator = current; + + // return current; + + static const float CURRENT_LOWCHANNEL_MAX = 75.0; //Amps + static const float CURRENT_LOWCHANNEL_MIN = -75.0; //Amps + // static const float CURRENT_SUPPLY_VOLTAGE = 5.038; + static const float CURRENT_ADC_RESOLUTION = 5.0 / MAX_ADC_RESOLUTION; + + static const float CURRENT_LOWCHANNEL_OFFSET = 2.500; // Calibrated with current = 0A + static const float CURRENT_HIGHCHANNEL_OFFSET = 2.500; // Calibrated with current = 0A + + static const float HIGHCHANNEL_GAIN = 1 / 0.0041; // Calibrated with current = 5A, 10A, 20A + static const float LOWCHANNEL_GAIN = 1 / 0.0267; + + // Change ADC channel to read the high current sensor + change_adc1_channel(VOUT_CHANNEL); + HAL_ADC_Start(&hadc1); + HAL_ADC_PollForConversion(&hadc1, HAL_MAX_DELAY); + int raw_low_current = HAL_ADC_GetValue(&hadc1); + + HAL_ADC_Start(&hadc2); + HAL_ADC_PollForConversion(&hadc2, HAL_MAX_DELAY); + int raw_high_current = HAL_ADC_GetValue(&hadc2); + + change_adc1_channel(REF_CHANNEL); + HAL_ADC_Start(&hadc1); + HAL_ADC_PollForConversion(&hadc1, HAL_MAX_DELAY); + int ref_5V = HAL_ADC_GetValue(&hadc1); + + int16_t ref_voltage_raw = (int16_t)(1000.0f * ((float)ref_5V * CURRENT_ADC_RESOLUTION)); + + int16_t high_current_voltage_raw = (int16_t)(1000.0f * ((float)raw_high_current * CURRENT_ADC_RESOLUTION)); + high_current_voltage_raw = (int16_t)(5000.0f * high_current_voltage_raw / (float) ref_voltage_raw) ; + + int16_t high_current = (high_current_voltage_raw - (1000 * CURRENT_HIGHCHANNEL_OFFSET)) * (1/4.0f); //* (HIGHCHANNEL_GAIN/100.0f))/1000; + + int16_t low_current_voltage_raw = (int16_t)(1000.0f * ((float)raw_low_current * CURRENT_ADC_RESOLUTION)); + low_current_voltage_raw = (int16_t)(5000.0f * low_current_voltage_raw / (float) ref_voltage_raw) ; + + int16_t low_current = (float)(low_current_voltage_raw - (1000 * CURRENT_LOWCHANNEL_OFFSET)) * (1/26.7); //* (LOWCHANNEL_GAIN/100.0f))/1000; + + // If the current is scoped within the range of the low channel, use the low channel + + + if((low_current < CURRENT_LOWCHANNEL_MAX - 5.0 && low_current >= 0) || (low_current > CURRENT_LOWCHANNEL_MIN + 5.0 && low_current < 0)) + { + //printf("\rLow Current: %d\n", -low_current); + return -low_current; + } - return -high_current; + //printf("\rHigh Current: %d\n", -high_current); + return -high_current; } -void compute_send_mc_message(uint16_t user_max_charge, uint16_t user_max_discharge) +void compute_send_mc_discharge_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { - uint16_t maxDischarge; - uint16_t maxCharge; + struct __attribute__((__packed__)){ + uint16_t max_discharge; + } discharge_data; - } mc_msg_data; + /* scale to A * 10 */ + discharge_data.max_discharge = 10 * bmsdata->discharge_limit; - mc_msg_data.maxCharge = user_max_charge; - mc_msg_data.maxDischarge = user_max_discharge; + /* convert to big endian */ + endian_swap(&discharge_data.max_discharge, sizeof(discharge_data.max_discharge)); - can_msg_t mc_msg; - mc_msg.id = 0x00; // TODO replace with correct ID; - mc_msg.len = sizeof(mc_msg_data); - memcpy(mc_msg.data, &mc_msg_data, sizeof(mc_msg_data)); + + can_msg_t mc_msg = {0}; + mc_msg.id = 0x156; // 0x0A is the dcl id, 0x22 is the device id set by us + mc_msg.len = 8; + memcpy(mc_msg.data, &discharge_data, sizeof(discharge_data)); + + can_send_msg(&can1, &mc_msg); +} + +void compute_send_mc_charge_message(acc_data_t* bmsdata) +{ + + struct __attribute__((__packed__)){ + int16_t max_charge; + } charge_data; + + /* scale to A * 10 */ + charge_data.max_charge = -10 * bmsdata->charge_limit; + + /* convert to big endian */ + endian_swap(&charge_data.max_charge, sizeof(charge_data.max_charge)); + + can_msg_t mc_msg = {0}; + mc_msg.id = 0x176; // 0x0A is the dcl id, 0x157 is the device id set by us + mc_msg.len = 8; + memcpy(mc_msg.data, &charge_data, sizeof(charge_data)); can_send_msg(&can1, &mc_msg); } @@ -178,7 +284,7 @@ void compute_send_mc_message(uint16_t user_max_charge, uint16_t user_max_dischar void compute_send_acc_status_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint16_t packVolt; uint16_t pack_current; uint16_t pack_ah; @@ -186,23 +292,34 @@ void compute_send_acc_status_message(acc_data_t* bmsdata) uint8_t pack_health; } acc_status_msg_data; - acc_status_msg_data.packVolt = __builtin_bswap16(bmsdata->pack_voltage); - acc_status_msg_data.pack_current = __builtin_bswap16((uint16_t)(bmsdata->pack_current)); // convert with 2s complement - acc_status_msg_data.pack_ah = __builtin_bswap16(0); + acc_status_msg_data.packVolt = bmsdata->pack_voltage; + acc_status_msg_data.pack_current = (uint16_t) (bmsdata->pack_current); // convert with 2s complement + acc_status_msg_data.pack_ah = 0; acc_status_msg_data.pack_soc = bmsdata->soc; acc_status_msg_data.pack_health = 0; + /* convert to big endian */ + endian_swap(&acc_status_msg_data.packVolt, sizeof(acc_status_msg_data.packVolt)); + endian_swap(&acc_status_msg_data.pack_current, sizeof(acc_status_msg_data.pack_current)); + endian_swap(&acc_status_msg_data.pack_ah, sizeof(acc_status_msg_data.pack_ah)); + can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x80; acc_msg.len = sizeof(acc_status_msg_data); memcpy(acc_msg.data, &acc_status_msg_data, sizeof(acc_status_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } void compute_send_bms_status_message(acc_data_t* bmsdata, int bms_state, bool balance) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint8_t state; uint32_t fault; int8_t temp_avg; @@ -216,33 +333,47 @@ void compute_send_bms_status_message(acc_data_t* bmsdata, int bms_state, bool ba bms_status_msg_data.temp_internal = (uint8_t)(0); bms_status_msg_data.balance = (uint8_t)(balance); + /* convert to big endian */ + endian_swap(&bms_status_msg_data.fault, sizeof(bms_status_msg_data.fault)); + can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; - acc_msg.len = sizeof(bms_status_msg_data); + acc_msg.id = 0x81; + acc_msg.len = sizeof(bms_status_msg_data); memcpy(acc_msg.data, &bms_status_msg_data, sizeof(bms_status_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + can_send_msg(line, &acc_msg); } void compute_send_shutdown_ctrl_message(uint8_t mpe_state) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint8_t mpeState; } shutdown_control_msg_data; shutdown_control_msg_data.mpeState = mpe_state; can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x82; acc_msg.len = sizeof(shutdown_control_msg_data); memcpy(acc_msg.data, &shutdown_control_msg_data, sizeof(shutdown_control_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } void compute_send_cell_data_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint16_t high_cell_voltage; uint8_t high_cell_id; uint16_t low_cell_voltage; @@ -251,24 +382,35 @@ void compute_send_cell_data_message(acc_data_t* bmsdata) } cell_data_msg_data; cell_data_msg_data.high_cell_voltage = bmsdata->max_voltage.val; - cell_data_msg_data.high_cell_id = bmsdata->max_voltage.chipIndex; + cell_data_msg_data.high_cell_id = (bmsdata->max_voltage.chipIndex << 4) | bmsdata->max_voltage.cellNum; cell_data_msg_data.low_cell_voltage = bmsdata->min_voltage.val; cell_data_msg_data.low_cell_id = (bmsdata->min_voltage.chipIndex << 4) | bmsdata->min_voltage.cellNum; cell_data_msg_data.volt_avg = bmsdata->avg_voltage; + /* convert to big endian */ + endian_swap(&cell_data_msg_data.high_cell_voltage, sizeof(cell_data_msg_data.high_cell_voltage)); + endian_swap(&cell_data_msg_data.low_cell_voltage, sizeof(cell_data_msg_data.low_cell_voltage)); + endian_swap(&cell_data_msg_data.volt_avg, sizeof(cell_data_msg_data.volt_avg)); + can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x83; acc_msg.len = sizeof(cell_data_msg_data); memcpy(acc_msg.data, &cell_data_msg_data, sizeof(cell_data_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } void compute_send_cell_voltage_message(uint8_t cell_id, uint16_t instant_voltage, uint16_t internal_Res, uint8_t shunted, uint16_t open_voltage) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint8_t cellID; uint16_t instantVoltage; uint16_t internalResistance; @@ -277,48 +419,64 @@ void compute_send_cell_voltage_message(uint8_t cell_id, uint16_t instant_voltage } cell_voltage_msg_data; cell_voltage_msg_data.cellID = cell_id; - cell_voltage_msg_data.instantVoltage = __builtin_bswap16(instant_voltage); - cell_voltage_msg_data.internalResistance = __builtin_bswap16(internal_Res); + cell_voltage_msg_data.instantVoltage = instant_voltage; + cell_voltage_msg_data.internalResistance = internal_Res; cell_voltage_msg_data.shunted = shunted; - cell_voltage_msg_data.openVoltage = __builtin_bswap16(open_voltage); + cell_voltage_msg_data.openVoltage = open_voltage; + + /* convert to big endian */ + endian_swap(&cell_voltage_msg_data.instantVoltage, sizeof(cell_voltage_msg_data.instantVoltage)); + endian_swap(&cell_voltage_msg_data.internalResistance, sizeof(cell_voltage_msg_data.internalResistance)); + endian_swap(&cell_voltage_msg_data.openVoltage, sizeof(cell_voltage_msg_data.openVoltage)); can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x87; acc_msg.len = sizeof(cell_voltage_msg_data); memcpy(acc_msg.data, &cell_voltage_msg_data, sizeof(cell_voltage_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } void compute_send_current_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint16_t dcl; - uint16_t ccl; + int16_t ccl; uint16_t pack_curr; } current_status_msg_data; current_status_msg_data.dcl = bmsdata->discharge_limit; - current_status_msg_data.ccl = bmsdata->charge_limit; + current_status_msg_data.ccl = -1 * bmsdata->charge_limit; current_status_msg_data.pack_curr = bmsdata->pack_current; + /* convert to big endian */ + endian_swap(¤t_status_msg_data.dcl, sizeof(current_status_msg_data.dcl)); + endian_swap(¤t_status_msg_data.ccl, sizeof(current_status_msg_data.ccl)); + endian_swap(¤t_status_msg_data.pack_curr, sizeof(current_status_msg_data.pack_curr)); + can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x86; acc_msg.len = sizeof(current_status_msg_data); memcpy(acc_msg.data, ¤t_status_msg_data, sizeof(current_status_msg_data)); - can_send_msg(&can1, &acc_msg); -} + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif -// TODO ADD THIS BACK -// void compute_mc_callback(const CAN_message_t& currentStatusMsg) -// { -// return; -// } + can_send_msg(line, &acc_msg); +} void compute_send_cell_temp_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ uint16_t max_cell_temp; uint8_t max_cell_id; uint16_t min_cell_temp; @@ -332,65 +490,129 @@ void compute_send_cell_temp_message(acc_data_t* bmsdata) cell_temp_msg_data.min_cell_id = (bmsdata->min_temp.chipIndex << 4) | (bmsdata->min_temp.cellNum - 17); cell_temp_msg_data.average_temp = bmsdata->avg_temp; + /* convert to big endian */ + endian_swap(&cell_temp_msg_data.max_cell_temp, sizeof(cell_temp_msg_data.max_cell_temp)); + endian_swap(&cell_temp_msg_data.min_cell_temp, sizeof(cell_temp_msg_data.min_cell_temp)); + endian_swap(&cell_temp_msg_data.average_temp, sizeof(cell_temp_msg_data.average_temp)); + can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x84; acc_msg.len = sizeof(cell_temp_msg_data); memcpy(acc_msg.data, &cell_temp_msg_data, sizeof(cell_temp_msg_data)); - can_send_msg(&can1, &acc_msg); + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } void compute_send_segment_temp_message(acc_data_t* bmsdata) { - struct __attribute__((packed)) { + struct __attribute__((__packed__)){ int8_t segment1_average_temp; int8_t segment2_average_temp; int8_t segment3_average_temp; int8_t segment4_average_temp; + int8_t segment5_average_temp; + int8_t segment6_average_temp; + } segment_temp_msg_data; segment_temp_msg_data.segment1_average_temp = bmsdata->segment_average_temps[0]; segment_temp_msg_data.segment2_average_temp = bmsdata->segment_average_temps[1]; segment_temp_msg_data.segment3_average_temp = bmsdata->segment_average_temps[2]; segment_temp_msg_data.segment4_average_temp = bmsdata->segment_average_temps[3]; - - uint8_t buff[4] = { 0 }; - memcpy(buff, &segment_temp_msg_data, sizeof(segment_temp_msg_data)); + segment_temp_msg_data.segment5_average_temp = bmsdata->segment_average_temps[4]; + segment_temp_msg_data.segment6_average_temp = bmsdata->segment_average_temps[5]; can_msg_t acc_msg; - acc_msg.id = 0x00; // TODO replace with correct ID; + acc_msg.id = 0x85; acc_msg.len = sizeof(segment_temp_msg_data); memcpy(acc_msg.data, &segment_temp_msg_data, sizeof(segment_temp_msg_data)); - can_send_msg(&can1, &acc_msg); -} + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif -uint8_t calc_charger_led_state(acc_data_t* bms_data) + can_send_msg(line, &acc_msg); +} +void compute_send_fault_message(uint8_t status, int16_t curr, int16_t in_dcl) { - enum LED_state { - RED_BLINKING = 0x00, - RED_CONSTANT = 0x01, - YELLOW_BLINKING = 0x02, - YELLOW_CONSTANT = 0x03, - GREEN_BLINKING = 0x04, - GREEN_CONSTANT = 0x05, - RED_GREEN_BLINKING = 0x06 - }; - - if ((bms_data->soc < 80) && (bms_data->pack_current > .5 * 10)) { - return RED_BLINKING; - } else if ((bms_data->soc < 80) && (bms_data->pack_current <= .5 * 10)) { - return RED_CONSTANT; - } else if ((bms_data->soc >= 80 && bms_data->soc < 95) && (bms_data->pack_current > .5 * 10)) { - return YELLOW_BLINKING; - } else if ((bms_data->soc >= 80 && bms_data->soc < 95) && (bms_data->pack_current <= .5 * 10)) { - return YELLOW_CONSTANT; - } else if ((bms_data->soc >= 95) && (bms_data->pack_current > .5 * 10)) { - return GREEN_BLINKING; - } else if ((bms_data->soc >= 95) && (bms_data->pack_current <= .5 * 10)) { - return GREEN_CONSTANT; - } else { - return RED_GREEN_BLINKING; - } + struct __attribute__((__packed__)){ + uint8_t status; + int16_t pack_curr; + int16_t dcl; + } fault_msg_data; + + fault_msg_data.status = status; + fault_msg_data.pack_curr = curr; + fault_msg_data.dcl = in_dcl; + + endian_swap(&fault_msg_data.pack_curr, sizeof(fault_msg_data.pack_curr)); + endian_swap(&fault_msg_data.dcl, sizeof(fault_msg_data.dcl)); + + can_msg_t acc_msg; + acc_msg.id = 0x703; + acc_msg.len = 5; + memcpy(acc_msg.data, &fault_msg_data, sizeof(fault_msg_data)); + + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); } +void compute_send_voltage_noise_message(acc_data_t* bmsdata) +{ + struct __attribute__((__packed__)){ + uint8_t seg1_noise; + uint8_t seg2_noise; + uint8_t seg3_noise; + uint8_t seg4_noise; + uint8_t seg5_noise; + uint8_t seg6_noise; + } voltage_noise_msg_data; + + voltage_noise_msg_data.seg1_noise = bmsdata->segment_noise_percentage[0]; + voltage_noise_msg_data.seg2_noise = bmsdata->segment_noise_percentage[1]; + voltage_noise_msg_data.seg3_noise = bmsdata->segment_noise_percentage[2]; + voltage_noise_msg_data.seg4_noise = bmsdata->segment_noise_percentage[3]; + voltage_noise_msg_data.seg5_noise = bmsdata->segment_noise_percentage[4]; + voltage_noise_msg_data.seg6_noise = bmsdata->segment_noise_percentage[5]; + + can_msg_t acc_msg; + acc_msg.id = 0x88; + acc_msg.len = sizeof(voltage_noise_msg_data); + memcpy(acc_msg.data, &voltage_noise_msg_data, sizeof(voltage_noise_msg_data)); + + #ifdef CHARGING_ENABLED + can_t* line = &can2; + #else + can_t* line = &can1; + #endif + + can_send_msg(line, &acc_msg); +} +void change_adc1_channel(uint8_t channel) +{ + + ADC_ChannelConfTypeDef sConfig = {0}; + + if (channel == REF_CHANNEL) sConfig.Channel = ADC_CHANNEL_9; + else if (channel == VOUT_CHANNEL) sConfig.Channel = ADC_CHANNEL_15; + + sConfig.Rank = 1; + sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } +} diff --git a/Core/Src/main.c b/Core/Src/main.c index cd9f828..97fa2b7 100644 --- a/Core/Src/main.c +++ b/Core/Src/main.c @@ -13,9 +13,7 @@ /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ -// #include -// TODO: import and replace new watchdog library -//#include + #include "segment.h" #include "compute.h" #include "datastructs.h" @@ -47,15 +45,25 @@ /* USER CODE END PM */ /* Private variables ---------------------------------------------------------*/ +ADC_HandleTypeDef hadc1; +ADC_HandleTypeDef hadc2; +DMA_HandleTypeDef hdma_adc1; + CAN_HandleTypeDef hcan1; CAN_HandleTypeDef hcan2; I2C_HandleTypeDef hi2c1; +IWDG_HandleTypeDef hiwdg; + SPI_HandleTypeDef hspi1; SPI_HandleTypeDef hspi2; SPI_HandleTypeDef hspi3; +TIM_HandleTypeDef htim1; +TIM_HandleTypeDef htim2; +TIM_HandleTypeDef htim8; + UART_HandleTypeDef huart4; PCD_HandleTypeDef hpcd_USB_OTG_FS; @@ -67,6 +75,7 @@ acc_data_t *prev_acc_data = NULL; /* Private function prototypes -----------------------------------------------*/ void SystemClock_Config(void); static void MX_GPIO_Init(void); +static void MX_DMA_Init(void); static void MX_CAN1_Init(void); static void MX_CAN2_Init(void); static void MX_SPI1_Init(void); @@ -75,8 +84,18 @@ static void MX_SPI3_Init(void); static void MX_UART4_Init(void); static void MX_USB_OTG_FS_PCD_Init(void); static void MX_I2C1_Init(void); +static void MX_TIM1_Init(void); +static void MX_TIM2_Init(void); +static void MX_TIM8_Init(void); +static void MX_ADC1_Init(void); +static void MX_ADC2_Init(void); +static void MX_IWDG_Init(void); /* USER CODE BEGIN PFP */ +/* this is for the hardware watchdog ic. Currently not activated in hw */ +//void watchdog_init(void); +//void watchdog_pet(void); + /* USER CODE END PFP */ /* Private user code ---------------------------------------------------------*/ @@ -108,38 +127,47 @@ int _write(int file, char* ptr, int len) { const void print_bms_stats(acc_data_t *acc_data) { - static nertimer_t debug_stat_timer; static const uint16_t PRINT_STAT_WAIT = 500; //ms if(!is_timer_expired(&debug_stat_timer) && debug_stat_timer.active) return; - HAL_UART_Transmit(&huart4, (char*)"butts", 5, 1000); - //TODO get this from eeprom once implemented + //TODO get this from eeprom once implemented // question - should we read from eeprom here, or do that on loop and store locally? - //printf("Prev Fault: %#x", previousFault); - printf("Current: %f\r\n", (float)(acc_data->pack_current) / 10.0); + // printf("Prev Fault: %#x", previousFault); + printf("CAN Error:\t%d\r\n", HAL_CAN_GetError(&hcan1)); + printf("Current * 10: %d\r\n", (acc_data->pack_current)); printf("Min, Max, Avg Temps: %ld, %ld, %d\r\n", acc_data->min_temp.val, acc_data->max_temp.val, acc_data->avg_temp); - printf("Min, Max, Avg, Delta Voltages: %ld, %ld, %d, %d\n", acc_data->min_voltage.val, acc_data->max_voltage.val, acc_data->avg_voltage, acc_data->delt_voltage); + printf("Min, Max, Avg, Delta Voltages: %ld, %ld, %d, %d\r\n", acc_data->min_voltage.val, acc_data->max_voltage.val, acc_data->avg_voltage, acc_data->delt_voltage); printf("DCL: %d\r\n", acc_data->discharge_limit); printf("CCL: %d\r\n", acc_data->charge_limit); + printf("Cont CCL %d\r\n", acc_data->cont_CCL); printf("SoC: %d\r\n", acc_data->soc); printf("Is Balancing?: %d\r\n", segment_is_balancing()); printf("State: "); if (current_state == 0) printf("BOOT\r\n"); else if (current_state == 1) printf("READY\r\n"); else if (current_state == 2) printf("CHARGING\r\n"); - else if (current_state == 1) printf("FAULTED\r\n"); + else if (current_state == 3) printf("FAULTED: %X\r\n", acc_data->fault_code); + + printf("Voltage Noise Percent:\r\n"); + printf("Seg 1: %d\r\n", acc_data->segment_noise_percentage[0]); + printf("Seg 2: %d\r\n", acc_data->segment_noise_percentage[1]); + printf("Seg 3: %d\r\n", acc_data->segment_noise_percentage[2]); + printf("Seg 4: %d\r\n", acc_data->segment_noise_percentage[3]); + printf("Seg 5: %d\r\n", acc_data->segment_noise_percentage[4]); + printf("Seg 6: %d\r\n", acc_data->segment_noise_percentage[5]); + printf("Raw Cell Voltage:\r\n"); for(uint8_t c = 0; c < NUM_CHIPS; c++) { for(uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { - printf("%d\t", acc_data->chip_data[c].voltage_reading[cell]); + printf("%d\t", acc_data->chip_data[c].voltage[cell]); } printf("\r\n"); } - printf("Open Cell Voltage:\n"); + printf("Open Cell Voltage:\r\n"); for(uint8_t c = 0; c < NUM_CHIPS; c++) { for(uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) @@ -147,27 +175,47 @@ const void print_bms_stats(acc_data_t *acc_data) printf("%d\t", acc_data->chip_data[c].open_cell_voltage[cell]); } printf("\r\n"); -} + } - printf("Cell Temps:\r\n"); + printf("Thermistors with Disabling:\r\n"); for(uint8_t c = 0; c < NUM_CHIPS; c++) { - for(uint8_t cell = 17; cell < 28; cell++) - { - printf("%d\t", acc_data->chip_data[c].thermistor_reading[cell]); - } - printf("\r\n"); + printf("Chip %d: ", c); + + for (uint8_t cell = 0; cell < NUM_THERMS_PER_CHIP; cell++) { + + //if (THERM_DISABLE[c][cell]) continue; + printf("%d ", acc_data->chip_data[c].thermistor_value[cell]); + } + + printf("\r\n"); } + + printf("UnFiltered Thermistor Temps:\r\n"); + for(uint8_t c = 0; c < NUM_CHIPS; c++) + { + printf("Chip %d: ", c); + + for (uint8_t cell = 0; cell < NUM_THERMS_PER_CHIP; cell++) { - printf("Avg Cell Temps:\r\n"); + printf("%d ", acc_data->chip_data[c].thermistor_reading[cell]); + } + + printf("\r\n"); + } + + printf("Cell Temps:\r\n"); for(uint8_t c = 0; c < NUM_CHIPS; c++) { - for(uint8_t cell = 17; cell < 28; cell++) - { - printf("%d\t", acc_data->chip_data[c].thermistor_value[cell]); + printf("Chip %d: ", c); + + for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { + + printf("%d ", acc_data->chip_data[c].cell_temp[cell]); + } + + printf("\r\n"); } - printf("\r\n"); - } start_timer(&debug_stat_timer, PRINT_STAT_WAIT); } @@ -199,11 +247,12 @@ int main(void) SystemClock_Config(); /* USER CODE BEGIN SysInit */ - + HAL_Delay(500); /* USER CODE END SysInit */ /* Initialize all configured peripherals */ MX_GPIO_Init(); + MX_DMA_Init(); MX_CAN1_Init(); MX_CAN2_Init(); MX_SPI1_Init(); @@ -212,9 +261,30 @@ int main(void) MX_UART4_Init(); MX_USB_OTG_FS_PCD_Init(); MX_I2C1_Init(); + MX_TIM1_Init(); + MX_TIM2_Init(); + MX_TIM8_Init(); + MX_ADC1_Init(); + MX_ADC2_Init(); + MX_IWDG_Init(); /* USER CODE BEGIN 2 */ - - segment_init(); + //for (int i = 0; i < 58; i++) + //{ + // HAL_GPIO_WritePin(Debug_LEDB11_GPIO_Port, Debug_LEDB11_Pin, GPIO_PIN_SET); + // HAL_Delay(58-i); + // HAL_GPIO_WritePin(Debug_LEDB11_GPIO_Port, Debug_LEDB11_Pin, GPIO_PIN_RESET); + // HAL_GPIO_WritePin(Debug_LED_GPIO_Port, Debug_LED_Pin, GPIO_PIN_SET); + // HAL_Delay(58-i); + // HAL_GPIO_WritePin(Debug_LED_GPIO_Port, Debug_LED_Pin, GPIO_PIN_RESET); + // + //} + + + HAL_Delay(500); + //watchdog_init(); + segment_init(); + compute_init(); + /* USER CODE END 2 */ /* Infinite loop */ @@ -222,13 +292,11 @@ int main(void) for(;;) { /* Create a dynamically allocated structure */ - HAL_GPIO_TogglePin(Debug_LEDB11_GPIO_Port, Debug_LEDB11_Pin); - HAL_Delay(500); - //HAL_UART_Transmit(&huart4, (char*)"hello", 5, 1000); + //TODO add ISR/timer based debug LED toggle acc_data_t *acc_data = malloc(sizeof(acc_data_t)); - - //acc_data->faultCode = FAULTS_CLEAR; + acc_data->is_charger_connected = false; + acc_data->fault_code = FAULTS_CLEAR; /* * Collect all the segment data needed to perform analysis @@ -237,23 +305,24 @@ int main(void) segment_retrieve_data(acc_data->chip_data); acc_data->pack_current = compute_get_pack_current(); - /* Perform calculations on the data in the frame */ analyzer_push(acc_data); sm_handle_state(acc_data); /* check for inbound CAN */ - // get_can1_msg(); - // get_can2_msg(); - + //get_can1_msg(); + //get_can2_msg(); #ifdef DEBUG_STATS print_bms_stats(acc_data); #endif - //delay(10); // not sure if we need this in, it was in before + + HAL_IWDG_Refresh(&hiwdg); + } /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ + /* USER CODE END 3 */ } @@ -274,10 +343,12 @@ void SystemClock_Config(void) /** Initializes the RCC Oscillators according to the specified parameters * in the RCC_OscInitTypeDef structure. */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_LSI + |RCC_OSCILLATORTYPE_HSE; RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.LSIState = RCC_LSI_ON; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; RCC_OscInitStruct.PLL.PLLM = 15; @@ -304,6 +375,110 @@ void SystemClock_Config(void) } } +/** + * @brief ADC1 Initialization Function + * @param None + * @retval None + */ +static void MX_ADC1_Init(void) +{ + + /* USER CODE BEGIN ADC1_Init 0 */ + + /* USER CODE END ADC1_Init 0 */ + + ADC_ChannelConfTypeDef sConfig = {0}; + + /* USER CODE BEGIN ADC1_Init 1 */ + + /* USER CODE END ADC1_Init 1 */ + + /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion) + */ + hadc1.Instance = ADC1; + hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2; + hadc1.Init.Resolution = ADC_RESOLUTION_12B; + hadc1.Init.ScanConvMode = DISABLE; + hadc1.Init.ContinuousConvMode = DISABLE; + hadc1.Init.DiscontinuousConvMode = DISABLE; + hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; + hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START; + hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc1.Init.NbrOfConversion = 1; + hadc1.Init.DMAContinuousRequests = ENABLE; + hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV; + if (HAL_ADC_Init(&hadc1) != HAL_OK) + { + Error_Handler(); + } + + /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time. + */ + sConfig.Channel = ADC_CHANNEL_15; + sConfig.Rank = 1; + sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN ADC1_Init 2 */ + + /* USER CODE END ADC1_Init 2 */ + +} + +/** + * @brief ADC2 Initialization Function + * @param None + * @retval None + */ +static void MX_ADC2_Init(void) +{ + + /* USER CODE BEGIN ADC2_Init 0 */ + + /* USER CODE END ADC2_Init 0 */ + + ADC_ChannelConfTypeDef sConfig = {0}; + + /* USER CODE BEGIN ADC2_Init 1 */ + + /* USER CODE END ADC2_Init 1 */ + + /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion) + */ + hadc2.Instance = ADC2; + hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2; + hadc2.Init.Resolution = ADC_RESOLUTION_12B; + hadc2.Init.ScanConvMode = DISABLE; + hadc2.Init.ContinuousConvMode = DISABLE; + hadc2.Init.DiscontinuousConvMode = DISABLE; + hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; + hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START; + hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc2.Init.NbrOfConversion = 1; + hadc2.Init.DMAContinuousRequests = DISABLE; + hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV; + if (HAL_ADC_Init(&hadc2) != HAL_OK) + { + Error_Handler(); + } + + /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time. + */ + sConfig.Channel = ADC_CHANNEL_8; + sConfig.Rank = 1; + sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES; + if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN ADC2_Init 2 */ + + /* USER CODE END ADC2_Init 2 */ + +} + /** * @brief CAN1 Initialization Function * @param None @@ -320,13 +495,13 @@ static void MX_CAN1_Init(void) /* USER CODE END CAN1_Init 1 */ hcan1.Instance = CAN1; - hcan1.Init.Prescaler = 16; + hcan1.Init.Prescaler = 2; hcan1.Init.Mode = CAN_MODE_NORMAL; hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ; - hcan1.Init.TimeSeg1 = CAN_BS1_1TQ; - hcan1.Init.TimeSeg2 = CAN_BS2_1TQ; + hcan1.Init.TimeSeg1 = CAN_BS1_13TQ; + hcan1.Init.TimeSeg2 = CAN_BS2_2TQ; hcan1.Init.TimeTriggeredMode = DISABLE; - hcan1.Init.AutoBusOff = DISABLE; + hcan1.Init.AutoBusOff = ENABLE; hcan1.Init.AutoWakeUp = DISABLE; hcan1.Init.AutoRetransmission = DISABLE; hcan1.Init.ReceiveFifoLocked = DISABLE; @@ -357,11 +532,11 @@ static void MX_CAN2_Init(void) /* USER CODE END CAN2_Init 1 */ hcan2.Instance = CAN2; - hcan2.Init.Prescaler = 16; + hcan2.Init.Prescaler = 2; hcan2.Init.Mode = CAN_MODE_NORMAL; hcan2.Init.SyncJumpWidth = CAN_SJW_1TQ; - hcan2.Init.TimeSeg1 = CAN_BS1_1TQ; - hcan2.Init.TimeSeg2 = CAN_BS2_1TQ; + hcan2.Init.TimeSeg1 = CAN_BS1_13TQ; + hcan2.Init.TimeSeg2 = CAN_BS2_2TQ; hcan2.Init.TimeTriggeredMode = DISABLE; hcan2.Init.AutoBusOff = DISABLE; hcan2.Init.AutoWakeUp = DISABLE; @@ -412,6 +587,34 @@ static void MX_I2C1_Init(void) } +/** + * @brief IWDG Initialization Function + * @param None + * @retval None + */ +static void MX_IWDG_Init(void) +{ + + /* USER CODE BEGIN IWDG_Init 0 */ + + /* USER CODE END IWDG_Init 0 */ + + /* USER CODE BEGIN IWDG_Init 1 */ + + /* USER CODE END IWDG_Init 1 */ + hiwdg.Instance = IWDG; + hiwdg.Init.Prescaler = IWDG_PRESCALER_32; + hiwdg.Init.Reload = 4095; + if (HAL_IWDG_Init(&hiwdg) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN IWDG_Init 2 */ + + /* USER CODE END IWDG_Init 2 */ + +} + /** * @brief SPI1 Initialization Function * @param None @@ -435,7 +638,7 @@ static void MX_SPI1_Init(void) hspi1.Init.CLKPolarity = SPI_POLARITY_HIGH; hspi1.Init.CLKPhase = SPI_PHASE_2EDGE; hspi1.Init.NSS = SPI_NSS_SOFT; - hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; + hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB; hspi1.Init.TIMode = SPI_TIMODE_DISABLE; hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; @@ -526,6 +729,217 @@ static void MX_SPI3_Init(void) } +/** + * @brief TIM1 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM1_Init(void) +{ + + /* USER CODE BEGIN TIM1_Init 0 */ + + /* USER CODE END TIM1_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_OC_InitTypeDef sConfigOC = {0}; + TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0}; + + /* USER CODE BEGIN TIM1_Init 1 */ + + /* USER CODE END TIM1_Init 1 */ + htim1.Instance = TIM1; + htim1.Init.Prescaler = 0; + htim1.Init.CounterMode = TIM_COUNTERMODE_UP; + htim1.Init.Period = 65535; + htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim1.Init.RepetitionCounter = 0; + htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim1) != HAL_OK) + { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_Init(&htim1) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + sConfigOC.OCMode = TIM_OCMODE_PWM1; + sConfigOC.Pulse = 0; + sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) + { + Error_Handler(); + } + sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE; + sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE; + sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; + sBreakDeadTimeConfig.DeadTime = 0; + sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; + sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH; + sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; + if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM1_Init 2 */ + + /* USER CODE END TIM1_Init 2 */ + HAL_TIM_MspPostInit(&htim1); + +} + +/** + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) +{ + + /* USER CODE BEGIN TIM2_Init 0 */ + + /* USER CODE END TIM2_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + + /* USER CODE BEGIN TIM2_Init 1 */ + + /* USER CODE END TIM2_Init 1 */ + htim2.Instance = TIM2; + htim2.Init.Prescaler = 0; + htim2.Init.CounterMode = TIM_COUNTERMODE_UP; + htim2.Init.Period = 4294967295; + htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim2) != HAL_OK) + { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM2_Init 2 */ + + /* USER CODE END TIM2_Init 2 */ + +} + +/** + * @brief TIM8 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM8_Init(void) +{ + + /* USER CODE BEGIN TIM8_Init 0 */ + + /* USER CODE END TIM8_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_OC_InitTypeDef sConfigOC = {0}; + TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0}; + + /* USER CODE BEGIN TIM8_Init 1 */ + + /* USER CODE END TIM8_Init 1 */ + htim8.Instance = TIM8; + htim8.Init.Prescaler = 0; + htim8.Init.CounterMode = TIM_COUNTERMODE_UP; + htim8.Init.Period = 65535; + htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim8.Init.RepetitionCounter = 0; + htim8.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim8) != HAL_OK) + { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + if (HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_Init(&htim8) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + sConfigOC.OCMode = TIM_OCMODE_PWM1; + sConfigOC.Pulse = 0; + sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_2) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) + { + Error_Handler(); + } + if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) + { + Error_Handler(); + } + sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE; + sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE; + sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; + sBreakDeadTimeConfig.DeadTime = 0; + sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; + sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH; + sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; + if (HAL_TIMEx_ConfigBreakDeadTime(&htim8, &sBreakDeadTimeConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM8_Init 2 */ + + /* USER CODE END TIM8_Init 2 */ + HAL_TIM_MspPostInit(&htim8); + +} + /** * @brief UART4 Initialization Function * @param None @@ -594,6 +1008,22 @@ static void MX_USB_OTG_FS_PCD_Init(void) } +/** + * Enable DMA controller clock + */ +static void MX_DMA_Init(void) +{ + + /* DMA controller clock enable */ + __HAL_RCC_DMA2_CLK_ENABLE(); + + /* DMA interrupt init */ + /* DMA2_Stream0_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn); + +} + /** * @brief GPIO Initialization Function * @param None @@ -613,8 +1043,8 @@ static void MX_GPIO_Init(void) __HAL_RCC_GPIOD_CLK_ENABLE(); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOC, FPGA_Reset_Pin|Communication_GPIO_Pin|Communication_GPIOC15_Pin|Communication_GPIOC0_Pin - |SPI_2_CS_Pin|Debug_LED_Pin, GPIO_PIN_RESET); + HAL_GPIO_WritePin(GPIOC, FPGA_Reset_Pin|Communication_GPIO_Pin|Communication_GPIOC0_Pin|SPI_2_CS_Pin + |Debug_LED_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ HAL_GPIO_WritePin(GPIOA, Fault_Output_Pin|SPI_1_CS_Pin|SPI_3_CS_Pin, GPIO_PIN_RESET); @@ -626,15 +1056,21 @@ static void MX_GPIO_Init(void) /*Configure GPIO pin Output Level */ HAL_GPIO_WritePin(External_GPIO_GPIO_Port, External_GPIO_Pin, GPIO_PIN_RESET); - /*Configure GPIO pins : FPGA_Reset_Pin Communication_GPIO_Pin Communication_GPIOC15_Pin Communication_GPIOC0_Pin - SPI_2_CS_Pin Debug_LED_Pin */ - GPIO_InitStruct.Pin = FPGA_Reset_Pin|Communication_GPIO_Pin|Communication_GPIOC15_Pin|Communication_GPIOC0_Pin - |SPI_2_CS_Pin|Debug_LED_Pin; + /*Configure GPIO pins : FPGA_Reset_Pin Communication_GPIO_Pin Communication_GPIOC0_Pin SPI_2_CS_Pin + Debug_LED_Pin */ + GPIO_InitStruct.Pin = FPGA_Reset_Pin|Communication_GPIO_Pin|Communication_GPIOC0_Pin|SPI_2_CS_Pin + |Debug_LED_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + /*Configure GPIO pin : PC15 */ + GPIO_InitStruct.Pin = GPIO_PIN_15; + GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + /*Configure GPIO pin : Interlock_Read_Pin */ GPIO_InitStruct.Pin = Interlock_Read_Pin; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; @@ -648,17 +1084,11 @@ static void MX_GPIO_Init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /*Configure GPIO pin : I_Sense_Pin */ - GPIO_InitStruct.Pin = I_Sense_Pin; + /*Configure GPIO pin : I_SenseB2_Pin */ + GPIO_InitStruct.Pin = I_SenseB2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(I_Sense_GPIO_Port, &GPIO_InitStruct); - - /*Configure GPIO pins : I_SenseB0_Pin I_SenseB1_Pin I_SenseB2_Pin */ - GPIO_InitStruct.Pin = I_SenseB0_Pin|I_SenseB1_Pin|I_SenseB2_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + HAL_GPIO_Init(I_SenseB2_GPIO_Port, &GPIO_InitStruct); /*Configure GPIO pins : Debug_LEDB11_Pin Watchdog_Out_Pin External_GPIOB3_Pin External_GPIOB4_Pin External_GPIOB5_Pin */ @@ -669,22 +1099,6 @@ static void MX_GPIO_Init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - /*Configure GPIO pins : Fan_PWM_Pin Fan_PWMC7_Pin Fan_PWMC8_Pin Fan_PWMC9_Pin */ - GPIO_InitStruct.Pin = Fan_PWM_Pin|Fan_PWMC7_Pin|Fan_PWMC8_Pin|Fan_PWMC9_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF3_TIM8; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - /*Configure GPIO pins : Fan_PWMA8_Pin Fan_PWMA10_Pin */ - GPIO_InitStruct.Pin = Fan_PWMA8_Pin|Fan_PWMA10_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /*Configure GPIO pin : External_GPIO_Pin */ GPIO_InitStruct.Pin = External_GPIO_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; @@ -698,6 +1112,21 @@ static void MX_GPIO_Init(void) /* USER CODE BEGIN 4 */ +void watchdog_init(void) +{ + HAL_GPIO_WritePin(Watchdog_Out_GPIO_Port, Watchdog_Out_Pin, GPIO_PIN_SET); + //HAL_Delay(1); // shouldn't be needed but here in case +} + +void watchdog_pet(void) +{ + + HAL_GPIO_WritePin(Watchdog_Out_GPIO_Port, Watchdog_Out_Pin, GPIO_PIN_SET); + //HAL_Delay(1); + HAL_GPIO_WritePin(Watchdog_Out_GPIO_Port, Watchdog_Out_Pin, GPIO_PIN_RESET); + +} + /* USER CODE END 4 */ /** diff --git a/Core/Src/segment.c b/Core/Src/segment.c index a58a461..8ccebbd 100644 --- a/Core/Src/segment.c +++ b/Core/Src/segment.c @@ -9,7 +9,9 @@ #define VOLTAGE_WAIT_TIME 100 /* ms */ #define THERM_AVG 15 /* Number of values to average */ #define MAX_VOLT_DELTA 2500 -#define MAX_VOLT_DELTA_COUNT 10 +#define MAX_CONSEC_NOISE 10 +#define GPIO_EXPANDER_ADDR 0x40 +#define GPIO_REGISTER_ADDR 0x09 //TODO ensure spi 1 is correct for talking to segs extern SPI_HandleTypeDef hspi1; @@ -19,7 +21,7 @@ uint8_t local_config[NUM_CHIPS][6] = {}; uint8_t therm_avg_counter = 0; chipdata_t *segment_data = NULL; -chipdata_t previous_data[NUM_CHIPS]; +chipdata_t previous_data[NUM_CHIPS] = {}; uint16_t discharge_commands[NUM_CHIPS] = {}; nertimer_t therm_timer; @@ -29,15 +31,18 @@ nertimer_t variance_timer; int voltage_error = 0; //not faulted int therm_error = 0; //not faulted +/* our segments are mapped backwards and in pairs, so they are read in 1,0 then 3,2, etc*/ +const int mapping_correction[12] = {1, 0, 3, 2, 5, 4, 7, 6, 9, 8, 11, 10}; + uint16_t therm_settle_time_ = 0; -const uint32_t VOLT_TEMP_CONV[91] = { 44260, 43970, 43670, 43450, 43030, 42690, 42340, 41980, 41620, - 41240, 40890, 40460, 40040, 39580, 39130, 38660, 38210, 37710, 37210, 36190, 35670, 35160, - 34620, 34080, 33550, 32990, 32390, 31880, 31270, 30690, 30160, 29590, 28990, 28450, 27880, - 27270, 26740, 26080, 25610, 25000, 24440, 23880, 23330, 22780, 22240, 21700, 21180, 20660, - 20150, 19640, 19140, 18650, 18170, 17700, 17230, 16780, 16330, 15890, 15470, 15030, 14640, - 14230, 13850, 13450, 13070, 12710, 11490, 11170, 10850, 10550, 10250, 9960, 9670, 9400, 9130, - 8870, 8620, 8370, 8130, 7900, 0 }; +const uint32_t VOLT_TEMP_CONV[106] = { +157300, 148800, 140300, 131800, 123300, 114800, 108772, 102744, 96716, 90688, 84660, 80328, 75996, 71664, 67332, +63000, 59860, 56720, 53580, 50440, 47300, 45004, 42708, 40412, 38116, 35820, 34124, 32428, 30732, 29036, 27340, +26076, 24812, 23548, 22284, 21020, 20074, 19128, 18182, 17236, 16290, 15576, 14862, 14148, 13434, 12720, 12176, +11632, 11088, 10544, 10000, 9584, 9168, 8753, 8337, 7921, 7600, 7279, 6957, 6636, 6315, 6065, 5816, 5566, 5317, +5067, 4872, 4676, 4481, 4285, 4090, 3936, 3782, 3627, 3473, 3319, 3197, 3075, 2953, 2831, 2709, 2612, 2514, 2417, +2319, 2222, 2144, 2066, 1988, 1910, 1832, 1769, 1706, 1644, 1581, 1518, 1467, 1416, 1366, 1315, 1264, 1223, 1181, 1140, 1098, 1057}; const int32_t VOLT_TEMP_CALIB_OFFSET = 0; @@ -59,7 +64,7 @@ void segment_init() ltc68041 = malloc(sizeof(ltc_config)); LTC6804_initialize(ltc68041, &hspi1, GPIOA, SPI_1_CS_Pin); - pull_chip_configuration(); + pull_chip_configuration(); for (int c = 0; c < NUM_CHIPS; c++) { local_config[c][0] = 0xF8; @@ -70,105 +75,44 @@ void segment_init() local_config[c][5] = 0x00; } push_chip_configuration(); + + start_timer(&voltage_reading_timer, VOLTAGE_WAIT_TIME); + start_timer(&therm_timer, THERM_WAIT_TIME); + + uint8_t i2c_write_data[NUM_CHIPS][3]; + + // Set GPIO expander to output + for(int chip = 0; chip < NUM_CHIPS; chip++) { + i2c_write_data[chip][0] = 0x40; // GPIO expander addr + i2c_write_data[chip][1] = 0x00; // GPIO direction addr + i2c_write_data[chip][2] = 0x00; // Set all to output + } + uint8_t comm_reg_data[NUM_CHIPS][6]; + + serialize_i2c_msg(i2c_write_data, comm_reg_data); + LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); + LTC6804_stcomm(ltc68041, 24); } -void select_therm(uint8_t therm) -{ +void select_therm(uint8_t therm){ /* Exit if out of range values */ - if (therm < 0 || therm > 32) { + if (therm < 1 || therm > 16){ return; } + uint8_t i2c_write_data[NUM_CHIPS][3]; uint8_t comm_reg_data[NUM_CHIPS][6]; - if (therm <= 8) { - /* Turn off competing multiplexor (therms 9-16) */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x92; - i2c_write_data[chip][1] = 0x00; - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 4); - - /* Turn on desired thermistor */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x90; - i2c_write_data[chip][1] = 0x08 + (therm - 1); - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - } else if (therm <= 16) { - /* Turn off competing multiplexor (therms 1-8) */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x90; - i2c_write_data[chip][1] = 0x00; - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - - /* Turn on desired thermistor */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x92; - i2c_write_data[chip][1] = 0x08 + (therm - 9); - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041,NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - } else if (therm <= 24) { - /* Turn off competing multiplexor (therms 25-32) */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x96; - i2c_write_data[chip][1] = 0x00; - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041,NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - - /* Turn on desired thermistor */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x94; - i2c_write_data[chip][1] = 0x08 + (therm - 17); - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - } else { - /* Turn off competing multiplexor (therms 17-24) */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x94; - i2c_write_data[chip][1] = 0x00; - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - - /* Turn on desired thermistor */ - for (int chip = 0; chip < NUM_CHIPS; chip++) { - i2c_write_data[chip][0] = 0x96; - i2c_write_data[chip][1] = 0x08 + (therm - 25); - i2c_write_data[chip][2] = 0x00; - } - serialize_i2c_msg(i2c_write_data, comm_reg_data); - push_chip_configuration(); - LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); - LTC6804_stcomm(ltc68041, 24); - } + + // select 0-16 on GPIO expander + for(int chip = 0; chip < NUM_CHIPS; chip++) { + i2c_write_data[chip][0] = GPIO_EXPANDER_ADDR; + i2c_write_data[chip][1] = GPIO_REGISTER_ADDR; + i2c_write_data[chip][2] = (therm - 1); // 0-15, will change multiplexer to select thermistor + } + serialize_i2c_msg(i2c_write_data, comm_reg_data); + push_chip_configuration(); + LTC6804_wrcomm(ltc68041, NUM_CHIPS, comm_reg_data); + LTC6804_stcomm(ltc68041, 24); } int pull_voltages() @@ -178,15 +122,17 @@ int pull_voltages() * just copy over the contents of the last good reading and the fault status * from the most recent attempt */ + + //int test_v[12] = {800, 800, 800, 800, 800, 800, 800, 800, 800, 800, 800, 800}; if (!is_timer_expired(&voltage_reading_timer) && voltage_reading_timer.active) { for (uint8_t i = 0; i < NUM_CHIPS; i++) { - memcpy(segment_data[i].voltage_reading, previous_data[i].voltage_reading, - sizeof(segment_data[i].voltage_reading)); + memcpy(segment_data[i].voltage, previous_data[i].voltage, + sizeof(segment_data[i].voltage)); } return voltage_error; } - uint16_t segment_voltages[NUM_CHIPS][12]; + uint16_t raw_voltages[NUM_CHIPS][12]; push_chip_configuration(); LTC6804_adcv(ltc68041); @@ -195,35 +141,64 @@ int pull_voltages() * If we received an incorrect PEC indicating a bad read * copy over the data from the last good read and indicate an error */ - if (LTC6804_rdcv(ltc68041, 0, NUM_CHIPS, segment_voltages) == -1) { + if (LTC6804_rdcv(ltc68041, 0, NUM_CHIPS, raw_voltages) == -1) { for (uint8_t i = 0; i < NUM_CHIPS; i++) { - memcpy(segment_data[i].voltage_reading, previous_data[i].voltage_reading, - sizeof(segment_data[i].voltage_reading)); + memcpy(segment_data[i].voltage, previous_data[i].voltage, + sizeof(segment_data[i].voltage)); + + printf("Bad voltage read\n"); } return 1; } /* If the read was successful, copy the voltage data */ for (uint8_t i = 0; i < NUM_CHIPS; i++) { - for (uint8_t j = 0; j < NUM_CELLS_PER_CHIP; j++) { - if (abs(segment_voltages[i][j] - previous_data[i].voltage_reading[j]) - > MAX_VOLT_DELTA) { - segment_data[i].voltage_reading[j] = previous_data[i].voltage_reading[j]; - segment_data[i].bad_volt_diff_count[j]++; - - if (segment_data[i].bad_volt_diff_count[j] > MAX_VOLT_DELTA_COUNT) { - segment_data[i].bad_volt_diff_count[j] = 0; - segment_data[i].voltage_reading[j] = segment_voltages[i][j]; - } + + int corrected_index = mapping_correction[i]; + + /* correction to account for missing index, see more info below */ + int dest_index = 0; + + for (uint8_t j = 0; j < NUM_CELLS_PER_CHIP + 1; j++) { + + /* cell 6 on every chip is not a real reading, we need to have the array skip this, and shift the remaining readings up one index*/ + if (j == 5) continue; + + segment_data[corrected_index].noise_reading[dest_index] = 0; + + if (raw_voltages[i][j] > (int)(10000 * (MAX_VOLT + 0.5)) || raw_voltages[i][j] < (int)(10000 * (MIN_VOLT - 0.5))) { + //if (previous_data[corrected_index].voltage[dest_index] > 45000 || previous_data[corrected_index].voltage[dest_index] < 20000) printf("poop\r\n"); + segment_data[corrected_index].voltage[dest_index] = previous_data[corrected_index].voltage[dest_index]; + segment_data[corrected_index].noise_reading[dest_index] = 1; + segment_data[corrected_index].consecutive_noise[dest_index]++; + //printf("New data: %d\r\n", segment_data[corrected_index].voltage[dest_index]); + // if (segment_data[corrected_index].consecutive_noise[dest_index] > MAX_CONSEC_NOISE) { + // segment_data[corrected_index].noise_reading[dest_index] = 0; + // segment_data[corrected_index].consecutive_noise[dest_index] = 0; + // segment_data[corrected_index].voltage[dest_index] = raw_voltages[i][j]; + // } } else { - segment_data[i].bad_volt_diff_count[j] = 0; - segment_data[i].voltage_reading[j] = segment_voltages[i][j]; + //printf("previous: %d\r\n", previous_data[corrected_index].voltage[dest_index]); + //if (previous_data[corrected_index].voltage[dest_index] > 45000 || previous_data[corrected_index].voltage[dest_index] < 20000) printf("pee\r\n"); + //else printf("wiping\r\n"); + segment_data[corrected_index].consecutive_noise[dest_index] = 0; + segment_data[corrected_index].voltage[dest_index] = raw_voltages[i][j]; + + if (raw_voltages[i][j] < 45000 && raw_voltages[i][j] > 24000) { + previous_data[corrected_index].voltage[dest_index] = raw_voltages[i][j]; + //printf("previous: %d\r\n", previous_data[corrected_index].voltage[dest_index]); + //printf("raw: %d\r\n", segment_data[corrected_index].voltage[dest_index]); + } + } + dest_index++; } } + /* Start the timer between readings if successful */ start_timer(&voltage_reading_timer, VOLTAGE_WAIT_TIME); + return 0; } @@ -242,49 +217,74 @@ int pull_thermistors() uint16_t raw_temp_voltages[NUM_CHIPS][6]; - /* Rotate through all thermistor pairs (we can poll two at once) */ - for (int therm = 1; therm <= 16; therm++) { - /* Sets multiplexors to select thermistors */ - select_therm(therm); - select_therm(therm + 16); - - push_chip_configuration(); - LTC6804_adax(ltc68041); /* Run ADC for AUX (GPIOs and refs) */ - LTC6804_rdaux(ltc68041, 0, NUM_CHIPS, raw_temp_voltages); /* Fetch ADC results from AUX registers */ + static uint8_t current_therm = 1; + if (current_therm > 16) { + current_therm = 1; + } + /* Sets multiplexors to select thermistors */ + select_therm(current_therm); + HAL_Delay(200); + //push_chip_configuration(); + LTC6804_clraux(ltc68041); + LTC6804_adax(ltc68041); /* Run ADC for AUX (GPIOs and refs) */ + HAL_Delay(3); + LTC6804_rdaux(ltc68041, 0, NUM_CHIPS, raw_temp_voltages); + /* Rotate through all thermistor pairs (we can poll two at once) */ + for (uint8_t therm = 1; therm <= (NUM_THERMS_PER_CHIP / 2); therm++) { for (uint8_t c = 0; c < NUM_CHIPS; c++) { + + int corrected_index = mapping_correction[c]; /* * Get current temperature LUT. Voltage is adjusted to account for 5V reg * fluctuations (index 2 is a reading of the ADC 5V ref) */ - segment_data[c].thermistor_reading[therm - 1] - = steinhart_est(raw_temp_voltages[c][0] * ((float)(raw_temp_voltages[c][2]) / 50000) - + VOLT_TEMP_CALIB_OFFSET); - segment_data[c].thermistor_reading[therm + 15] - = steinhart_est(raw_temp_voltages[c][1] * ((float)(raw_temp_voltages[c][2]) / 50000) - + VOLT_TEMP_CALIB_OFFSET); - - /* Directly update for a set time from start up due to therm voltages - * needing to settle */ - segment_data[c].thermistor_value[therm - 1] - = segment_data[c].thermistor_reading[therm - 1]; - segment_data[c].thermistor_value[therm + 15] - = segment_data[c].thermistor_reading[therm + 15]; - - if (raw_temp_voltages[c][0] == LTC_BAD_READ - || raw_temp_voltages[c][1] == LTC_BAD_READ) { - memcpy(segment_data[c].thermistor_reading, previous_data[c].thermistor_reading, - sizeof(segment_data[c].thermistor_reading)); - memcpy(segment_data[c].thermistor_value, previous_data[c].thermistor_value, - sizeof(segment_data[c].thermistor_value)); + if (therm == current_therm) { + /* see "thermister decoding" in confluence in shepherd software 22A */ + uint16_t steinhart_input_low = 10000 * (float)( ((float)raw_temp_voltages[c][2])/ (raw_temp_voltages[c][0]) - 1 ); + uint16_t steinhart_input_high = 10000 * (float)( ((float)raw_temp_voltages[c][2])/ (raw_temp_voltages[c][1]) - 1 ); + + segment_data[corrected_index].thermistor_reading[therm - 1] = steinhart_est(steinhart_input_low); + segment_data[corrected_index].thermistor_reading[therm + 15] = steinhart_est(steinhart_input_high); + + /* Directly update for a set time from start up due to therm voltages + * needing to settle */ + segment_data[corrected_index].thermistor_value[therm - 1] + = segment_data[corrected_index].thermistor_reading[therm - 1]; + segment_data[corrected_index].thermistor_value[therm + 15] + = segment_data[corrected_index].thermistor_reading[therm + 15]; + + if (raw_temp_voltages[c][0] == LTC_BAD_READ + || raw_temp_voltages[c][1] == LTC_BAD_READ + || segment_data[corrected_index].thermistor_value[therm - 1] > (MAX_CELL_TEMP + 5) + || segment_data[corrected_index].thermistor_value[therm + 15] > (MAX_CELL_TEMP + 5 ) + || segment_data[corrected_index].thermistor_value[therm - 1] < (MIN_CELL_TEMP - 5) + || segment_data[corrected_index].thermistor_value[therm + 15] < (MIN_CELL_TEMP - 5 )) { + memcpy(segment_data[corrected_index].thermistor_reading, previous_data[c].thermistor_reading, + sizeof(segment_data[corrected_index].thermistor_reading)); + memcpy(segment_data[corrected_index].thermistor_value, previous_data[c].thermistor_value, + sizeof(segment_data[corrected_index].thermistor_value)); + } + } + else { + segment_data[corrected_index].thermistor_reading[therm - 1] = previous_data[corrected_index].thermistor_reading[therm - 1]; + segment_data[corrected_index].thermistor_reading[therm + 15] = previous_data[corrected_index].thermistor_reading[therm + 15]; + + segment_data[corrected_index].thermistor_value[therm - 1] + = segment_data[corrected_index].thermistor_reading[therm - 1]; + segment_data[corrected_index].thermistor_value[therm + 15] + = segment_data[corrected_index].thermistor_reading[therm + 15]; } } } - start_timer(&therm_timer, THERM_WAIT_TIME); /* Start timer for next reading */ - variance_therm_check(); - // standard_dev_therm_check(); - // averaging_therm_check(); - discard_neutrals(); + current_therm++; + start_timer(&therm_timer, 100/*THERM_WAIT_TIME*/); /* Start timer for next reading */ + + /* the following algorithms were used to eliminate noise on Car 17D - keep them off if possible */ + //variance_therm_check(); + //standard_dev_therm_check(); + //averaging_therm_check(); + //discard_neutrals(); return 0; /* Read successfully */ } @@ -293,7 +293,7 @@ void segment_retrieve_data(chipdata_t databuf[NUM_CHIPS]) { segment_data = databuf; - /* Pull voltages and thermistors and indiacte if there was a problem during + /* Pull voltages and thermistors and indiacate if there was a problem during * retrieval */ voltage_error = pull_voltages(); therm_error = pull_thermistors(); @@ -362,10 +362,10 @@ void segment_configure_balancing(bool discharge_config[NUM_CHIPS][NUM_CELLS_PER_ { for (int c = 0; c < NUM_CHIPS; c++) { for (int cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { - if (discharge_config[c][cell]) - discharge_commands[c] |= 1 << cell; + if (discharge_config[mapping_correction[c]][cell]) + discharge_commands[mapping_correction[c]] |= 1 << cell; else - discharge_commands[c] &= ~(1 << cell); + discharge_commands[mapping_correction[c]] &= ~(1 << cell); } configure_discharge(c, discharge_commands[c]); @@ -420,12 +420,16 @@ void pull_chip_configuration() int8_t steinhart_est(uint16_t V) { - int i = 0; - while (V < VOLT_TEMP_CONV[i]) - i++; - return i + MIN_TEMP; -} + /* min temp - max temp with buffer on both */ + for (int i = -25; i < 80; i++) { + if (V > VOLT_TEMP_CONV[i + 25]) { + return i; + } + } + return 80; + +} void disable_gpio_pulldowns() { HAL_Delay(1000); @@ -591,4 +595,4 @@ void discard_neutrals() } } } -} \ No newline at end of file +} diff --git a/Core/Src/stateMachine.c b/Core/Src/stateMachine.c index 94eb636..49f1e0b 100644 --- a/Core/Src/stateMachine.c +++ b/Core/Src/stateMachine.c @@ -1,5 +1,6 @@ #include "stateMachine.h" #include +#include #define MIN(a, b) (((a) < (b)) ? (a) : (b)) extern UART_HandleTypeDef huart4; @@ -10,14 +11,20 @@ uint32_t bms_fault = FAULTS_CLEAR; BMSState_t current_state = BOOT_STATE; uint32_t previousFault = 0; -nertimer_t charge_timeout = { .active = false }; -nertimer_t charge_cut_off_timer = { .active = false }; +nertimer_t charger_settle_countup = { .active = false }; +nertimer_t charger_max_volt_timer = { .active = false }; +nertimer_t charger_settle_countdown = { .active = false }; nertimer_t can_msg_timer = { .active = false }; +extern TIM_HandleTypeDef htim1; +extern TIM_HandleTypeDef htim8; + bool entered_faulted = false; nertimer_t charger_message_timer; + +nertimer_t bootup_timer; static const uint16_t CHARGE_MESSAGE_WAIT = 250; /* ms */ const bool valid_transition_from_to[NUM_STATES][NUM_STATES] = { @@ -56,8 +63,10 @@ void handle_boot(acc_data_t* bmsdata) prevAccData = NULL; segment_enable_balancing(false); compute_enable_charging(false); + start_timer(&bootup_timer, 10000); + printf("Bootup timer started\r\n"); - + compute_set_fault(1); // bmsdata->fault_code = FAULTS_CLEAR; request_transition(READY_STATE); @@ -74,8 +83,8 @@ void init_ready() void handle_ready(acc_data_t* bmsdata) { /* check for charger connection */ - if (compute_charger_connected()) { - request_transition(CHARGING_STATE); + if (compute_charger_connected() && is_timer_expired(&bootup_timer)) { //TODO Fix once charger works + request_transition(READY_STATE); } else { sm_broadcast_current_limit(bmsdata); return; @@ -84,7 +93,7 @@ void handle_ready(acc_data_t* bmsdata) void init_charging() { - cancel_timer(&charge_timeout); + cancel_timer(&charger_settle_countup); return; } @@ -93,33 +102,25 @@ void handle_charging(acc_data_t* bmsdata) if (!compute_charger_connected()) { request_transition(READY_STATE); return; - } else { + + } + else { + /* Check if we should charge */ - if (sm_charging_check(bmsdata)) { - //TODO update to HAL - //digitalWrite(CHARGE_SAFETY_RELAY, 1); - compute_enable_charging(true); - } else { - //TODO update to HAL - //digitalWrite(CHARGE_SAFETY_RELAY, 0); - compute_enable_charging(false); - } + if (sm_charging_check(bmsdata)) compute_enable_charging(true); + else { compute_enable_charging(false); compute_send_charging_message(0, 0, bmsdata); } /* Check if we should balance */ - if (sm_balancing_check(bmsdata)) { - sm_balance_cells(bmsdata); - } else { - segment_enable_balancing(false); - } + if (sm_balancing_check(bmsdata)) sm_balance_cells(bmsdata); + else segment_enable_balancing(false); + /* Send CAN message, but not too often */ if (is_timer_expired(&charger_message_timer) || !is_timer_active(&charger_message_timer)) { compute_send_charging_message( - (MAX_CHARGE_VOLT * NUM_CELLS_PER_CHIP * NUM_CHIPS), bmsdata); + (MAX_CHARGE_VOLT * NUM_CELLS_PER_CHIP * NUM_CHIPS), 5, bmsdata); start_timer(&charger_message_timer, CHARGE_MESSAGE_WAIT); - } else { - //TODO update to HAL - //digitalWrite(CHARGE_SAFETY_RELAY, 0); + } } } @@ -140,13 +141,13 @@ void handle_faulted(acc_data_t* bmsdata) } if (bmsdata->fault_code == FAULTS_CLEAR) { - compute_set_fault(0); + compute_set_fault(1); request_transition(BOOT_STATE); return; } else { - compute_set_fault(1); + compute_set_fault(0); //TODO update to HAL //digitalWrite(CHARGE_SAFETY_RELAY, 0); @@ -156,10 +157,12 @@ void handle_faulted(acc_data_t* bmsdata) void sm_handle_state(acc_data_t* bmsdata) { - bmsdata->is_charger_connected = compute_charger_connected(); - bmsdata->max_temp.val = 75; - bmsdata->fault_code = sm_fault_return(bmsdata); + static uint8_t can_msg_to_send = 0; + enum {ACC_STATUS, CURRENT, BMS_STATUS, CELL_TEMP, CELL_DATA, SEGMENT_TEMP, MC_DISCHARGE, MC_CHARGE, MAX_MSGS}; + bmsdata->fault_code = sm_fault_return(bmsdata); + + //calculate_pwm(bmsdata); if (bmsdata->fault_code != FAULTS_CLEAR) { bmsdata->discharge_limit = 0; @@ -168,26 +171,48 @@ void sm_handle_state(acc_data_t* bmsdata) // TODO needs testing - (update, seems to work fine) handler_LUT[current_state](bmsdata); - compute_set_fan_speed(analyzer_calc_fan_pwm()); - sm_broadcast_current_limit(bmsdata); - char state_test[1] = "0"; - state_test[0] = current_state + '0'; + bmsdata->is_charger_connected = compute_charger_connected(); + sm_broadcast_current_limit(bmsdata); /* send relevant CAN msgs */ // clang-format off if (is_timer_expired(&can_msg_timer) || !is_timer_active(&can_msg_timer)) { - compute_send_acc_status_message(bmsdata); - compute_send_current_message(bmsdata); - compute_send_bms_status_message(bmsdata, current_state, segment_is_balancing()); - compute_send_cell_temp_message(bmsdata); - compute_send_cell_data_message(bmsdata); - compute_send_segment_temp_message(bmsdata); + switch (can_msg_to_send) { + case ACC_STATUS: + compute_send_acc_status_message(bmsdata); + break; + case CURRENT: + compute_send_current_message(bmsdata); + break; + case BMS_STATUS: + compute_send_bms_status_message(bmsdata, current_state, segment_is_balancing()); + break; + case CELL_TEMP: + compute_send_cell_temp_message(bmsdata); + break; + case CELL_DATA: + compute_send_cell_data_message(bmsdata); + break; + case SEGMENT_TEMP: + compute_send_segment_temp_message(bmsdata); + break; + case MC_DISCHARGE: + compute_send_mc_discharge_message(bmsdata); + break; + case MC_CHARGE: + compute_send_mc_charge_message(bmsdata); + break; + + default: + break; + } + start_timer(&can_msg_timer, CAN_MESSAGE_WAIT); + can_msg_to_send = (can_msg_to_send + 1) % MAX_MSGS; } // clang-format on - } void request_transition(BMSState_t next_state) @@ -223,23 +248,47 @@ uint32_t sm_fault_return(acc_data_t* accData) fault_table = (fault_eval_t*) malloc(NUM_FAULTS * sizeof(fault_eval_t)); // clang-format off // ___________FAULT ID____________ __________TIMER___________ _____________DATA________________ __OPERATOR__ __________________________THRESHOLD____________________________ _______TIMER LENGTH_________ _____________FAULT CODE_________________ ___OPERATOR 2__ _______________DATA 2______________ __THRESHOLD 2__ - fault_table[0] = (fault_eval_t) {.id = "Discharge Current Limit", .timer = ovr_curr_timer, .data_1 = fault_data->pack_current, .optype_1 = GT, .lim_1 = (fault_data->discharge_limit + DCDC_CURRENT_DRAW)*10*1.04, .timeout = OVER_CURR_TIME, .code = DISCHARGE_LIMIT_ENFORCEMENT_FAULT, .optype_2 = NOP/* ---------------------------UNUSED------------------- */ }; + fault_table[0] = (fault_eval_t) {.id = "Discharge Current Limit", .timer = ovr_curr_timer, .data_1 = fault_data->pack_current, .optype_1 = GT, .lim_1 = (fault_data->discharge_limit + DCDC_CURRENT_DRAW)*10 * CURR_ERR_MARG, .timeout = OVER_CURR_TIME, .code = DISCHARGE_LIMIT_ENFORCEMENT_FAULT, .optype_2 = NOP/* ---------------------------UNUSED------------------- */ }; fault_table[1] = (fault_eval_t) {.id = "Charge Current Limit", .timer = ovr_chgcurr_timer, .data_1 = fault_data->pack_current, .optype_1 = GT, .lim_1 = (fault_data->charge_limit)*10, .timeout = OVER_CHG_CURR_TIME, .code = CHARGE_LIMIT_ENFORCEMENT_FAULT, .optype_2 = LT, .data_2 = fault_data->pack_current, .lim_2 = 0 }; fault_table[2] = (fault_eval_t) {.id = "Low Cell Voltage", .timer = undr_volt_timer, .data_1 = fault_data->min_voltage.val, .optype_1 = LT, .lim_1 = MIN_VOLT * 10000, .timeout = UNDER_VOLT_TIME, .code = CELL_VOLTAGE_TOO_LOW, .optype_2 = NOP/* ---------------------------UNUSED-------------------*/ }; fault_table[3] = (fault_eval_t) {.id = "High Cell Voltage", .timer = ovr_chgvolt_timer, .data_1 = fault_data->max_voltage.val, .optype_1 = GT, .lim_1 = MAX_CHARGE_VOLT * 10000, .timeout = OVER_VOLT_TIME, .code = CELL_VOLTAGE_TOO_HIGH, .optype_2 = NOP/* ---------------------------UNUSED-------------------*/ }; fault_table[4] = (fault_eval_t) {.id = "High Cell Voltage", .timer = ovr_volt_timer, .data_1 = fault_data->max_voltage.val, .optype_1 = GT, .lim_1 = MAX_VOLT * 10000, .timeout = OVER_VOLT_TIME, .code = CELL_VOLTAGE_TOO_HIGH, .optype_2 = EQ, .data_2 = fault_data->is_charger_connected, .lim_2 = false }; - fault_table[5] = (fault_eval_t) {.id = "High Temp", .timer = high_temp_timer, .data_1 = fault_data->max_temp.val, .optype_1 = GT, .lim_1 = MAX_CELL_TEMP, .timeout = LOW_CELL_TIME, .code = PACK_TOO_HOT, .optype_2 = NOP/* ----------------------------------------------------*/ }; - fault_table[6] = (fault_eval_t) {.id = "Extremely Low Voltage", .timer = low_cell_timer, .data_1 = fault_data->min_voltage.val, .optype_1 = LT, .lim_1 = 900, .timeout = HIGH_TEMP_TIME, .code = LOW_CELL_VOLTAGE, .optype_2 = NOP/* --------------------------UNUSED--------------------*/ }; + fault_table[5] = (fault_eval_t) {.id = "High Temp", .timer = high_temp_timer, .data_1 = fault_data->max_temp.val, .optype_1 = GT, .lim_1 = MAX_CELL_TEMP, .timeout = HIGH_TEMP_TIME, .code = PACK_TOO_HOT, .optype_2 = NOP/* ----------------------------------------------------*/ }; + fault_table[6] = (fault_eval_t) {.id = "Extremely Low Voltage", .timer = low_cell_timer, .data_1 = fault_data->min_voltage.val, .optype_1 = LT, .lim_1 = 900, .timeout = LOW_CELL_TIME, .code = LOW_CELL_VOLTAGE, .optype_2 = NOP/* --------------------------UNUSED--------------------*/ }; fault_table[7] = (fault_eval_t) {.id = NULL}; + + cancel_timer(&ovr_curr_timer); + cancel_timer(&ovr_chgcurr_timer); + cancel_timer(&undr_volt_timer); + cancel_timer(&ovr_chgvolt_timer); + cancel_timer(&ovr_volt_timer); + cancel_timer(&low_cell_timer); + cancel_timer(&high_temp_timer); // clang-format on } + + else + { + fault_table[0].data_1 = fault_data->pack_current; + fault_table[0].lim_1 = (fault_data->discharge_limit + DCDC_CURRENT_DRAW)*10 * CURR_ERR_MARG; + fault_table[1].data_1 = fault_data->pack_current; + fault_table[1].lim_1 = (fault_data->charge_limit)*10; + fault_table[2].data_1 = fault_data->min_voltage.val; + fault_table[3].data_1 = fault_data->max_voltage.val; + fault_table[4].data_1 = fault_data->max_voltage.val; + fault_table[4].data_2 = fault_data->is_charger_connected; + fault_table[5].data_1 = fault_data->max_temp.val; + fault_table[6].data_1 = fault_data->min_voltage.val; + } + static uint32_t fault_status = 0; int incr = 0; while (fault_table[incr].id != NULL) { fault_status |= sm_fault_eval(&fault_table[incr]); incr++; } - + //TODO: Remove This !!!! + fault_status &= ~DISCHARGE_LIMIT_ENFORCEMENT_FAULT; return fault_status; } @@ -257,8 +306,8 @@ uint32_t sm_fault_eval(fault_eval_t* index) case LE: condition1 = index->data_1 <= index->lim_1; break; case EQ: condition1 = index->data_1 == index->lim_1; break; case NEQ: condition1 = index->data_1 != index->lim_1; break; - case NOP: - default: condition1 = true; + case NOP: condition1 = false; + default: condition1 = false; } switch (index->optype_2) @@ -269,49 +318,101 @@ uint32_t sm_fault_eval(fault_eval_t* index) case LE: condition2 = index->data_2 <= index->lim_2; break; case EQ: condition2 = index->data_2 == index->lim_2; break; case NEQ: condition2 = index->data_2 != index->lim_2; break; - case NOP: - default: condition2 = true; + case NOP: condition2 = false; + default: condition2 = false; } // clang-format on - if (!is_timer_active(&index->timer) && condition1 && condition2) + bool fault_present = ( (condition1 && condition2) || (condition1 && (index->optype_2 == NOP)) ); + if ((!(is_timer_active(&index->timer))) && !fault_present) { - start_timer(&index->timer, index->timeout); + return 0; } - else if (is_timer_active(&index->timer) && condition1 && condition2) { - if (is_timer_expired(&index->timer)) { + if (is_timer_active(&index->timer)) + { + if (!fault_present) + { + printf("\t\t\t*******Fault cleared: %s\r\n", index->id); + cancel_timer(&index->timer); + return 0; + } + + if (is_timer_expired(&index->timer) && fault_present) + { + printf("\t\t\t*******Faulted: %s\r\n", index->id); + compute_send_fault_message(2, index->data_1, index->lim_1); return index->code; } - if (!(condition1 && condition2)) { - cancel_timer(&index->timer); + + + else return 0; + + } + + else if (!is_timer_active(&index->timer) && fault_present) + { + + printf("\t\t\t*******Starting fault timer: %s\r\n", index->id); + start_timer(&index->timer, index->timeout); + if (index->code == DISCHARGE_LIMIT_ENFORCEMENT_FAULT) { + compute_send_fault_message(1, index->data_1, index->lim_1); } + + return 0; } - + /* if (index->code == CELL_VOLTAGE_TOO_LOW) { + printf("\t\t\t*******Not fautled!!!!!\t%d\r\n", !is_timer_active(&index->timer) && condition1 && condition2); + printf("More stats...\t:%d\t%d\r\n", is_timer_expired(&index->timer), index->timer.active); + } */ + printf("err should not get here"); return 0; } + +/* charger settle countup = 1 minute pause to let readings settle and get good OCV */ +/* charger settle countdown = 5 minute interval between 1 minute settle pauses */ +/* charger_max_volt_timer = interval of time when voltage is too high before trying to start again */ bool sm_charging_check(acc_data_t* bmsdata) -{ - if (!compute_charger_connected()) +{ + if (!compute_charger_connected()) { + printf("Charger not connected\r\n"); return false; - if (!is_timer_expired(&charge_timeout) && is_timer_active(&charge_timeout)) + } + + if (!is_timer_expired(&charger_settle_countup) && is_timer_active(&charger_settle_countup)) { + printf("Charger settle countup active\r\n"); + return false; + } + + if (!is_timer_expired(&charger_max_volt_timer) && is_timer_active(&charger_max_volt_timer)) { + printf("Charger max volt timer active\r\n"); + return false; + } + + if (bmsdata->max_voltage.val > MAX_CHARGE_VOLT*10000) { + start_timer(&charger_max_volt_timer, CHARGE_VOLT_TIMEOUT); + printf("Charger max volt timer started\r\n"); + printf("Max voltage: %d\r\n", bmsdata->max_voltage.val); return false; + } + + if (is_timer_active(&charger_settle_countdown)) { - if (bmsdata->max_voltage.val >= (MAX_CHARGE_VOLT * 10000) - && !charge_cut_off_timer.active){ - start_timer(&charge_cut_off_timer, 5000); - } else if (charge_cut_off_timer.active) { - if (is_timer_expired(&charge_cut_off_timer)) { - start_timer(&charge_timeout, CHARGE_TIMEOUT); + if (is_timer_expired(&charger_settle_countdown)) { + start_timer(&charger_settle_countup, CHARGE_SETL_TIMEOUT); return false; } - if (!(bmsdata->max_voltage.val >= (MAX_CHARGE_VOLT * 10000))) { - cancel_timer(&charge_cut_off_timer); - } + + else return true; + } + + else + { + start_timer(&charger_settle_countdown, CHARGE_SETL_TIMEUP); + return true; } - return true; } bool sm_balancing_check(acc_data_t* bmsdata) @@ -324,6 +425,9 @@ bool sm_balancing_check(acc_data_t* bmsdata) return false; if (bmsdata->delt_voltage <= (MAX_DELTA_V * 10000)) return false; + + if (is_timer_active(&charger_settle_countup) && !is_timer_expired(&charger_settle_countup)) + return false; return true; } @@ -371,7 +475,7 @@ void sm_balance_cells(acc_data_t* bms_data) * in voltages */ for (uint8_t chip = 0; chip < NUM_CHIPS; chip++) { for (uint8_t cell = 0; cell < NUM_CELLS_PER_CHIP; cell++) { - uint16_t delta = bms_data->chip_data[chip].voltage_reading[cell] + uint16_t delta = bms_data->chip_data[chip].voltage[cell] - (uint16_t)bms_data->min_voltage.val; if (delta > MAX_DELTA_V * 10000) balanceConfig[chip][cell] = true; @@ -393,3 +497,58 @@ void sm_balance_cells(acc_data_t* bms_data) segment_configure_balancing(balanceConfig); } + +void calculate_pwm(acc_data_t* bmsdata) +{ + // todo actually implement algorithm + // this should include: + // 1. set PWM based on temp of "nearby" cells + // 2. automate seleciton of htim rather than hardcode + + if (bmsdata->max_temp.val > 50) + { + compute_set_fan_speed(&htim1, FAN1, 100); + compute_set_fan_speed(&htim1, FAN2, 100); + compute_set_fan_speed(&htim8, FAN3, 100); + compute_set_fan_speed(&htim8, FAN4, 100); + compute_set_fan_speed(&htim8, FAN5, 100); + compute_set_fan_speed(&htim8, FAN6, 100); + return; + } + + else if (bmsdata->max_temp.val > 40) + { + compute_set_fan_speed(&htim1, FAN1, 50); + compute_set_fan_speed(&htim1, FAN2, 50); + compute_set_fan_speed(&htim8, FAN3, 50); + compute_set_fan_speed(&htim8, FAN4, 50); + compute_set_fan_speed(&htim8, FAN5, 50); + compute_set_fan_speed(&htim8, FAN6, 50); + return; + } + + else if (bmsdata->max_temp.val > 30) + { + compute_set_fan_speed(&htim1, FAN1, 25); + compute_set_fan_speed(&htim1, FAN2, 25); + compute_set_fan_speed(&htim8, FAN3, 25); + compute_set_fan_speed(&htim8, FAN4, 25); + compute_set_fan_speed(&htim8, FAN5, 25); + compute_set_fan_speed(&htim8, FAN6, 25); + return; + } + + else + { + compute_set_fan_speed(&htim1, FAN1, 0); + compute_set_fan_speed(&htim1, FAN2, 0); + compute_set_fan_speed(&htim8, FAN3, 0); + compute_set_fan_speed(&htim8, FAN4, 0); + compute_set_fan_speed(&htim8, FAN5, 0); + compute_set_fan_speed(&htim8, FAN6, 0); + return; + } + +} + + diff --git a/Core/Src/stm32f4xx_hal_msp.c b/Core/Src/stm32f4xx_hal_msp.c index 1ffb847..fb49ff2 100644 --- a/Core/Src/stm32f4xx_hal_msp.c +++ b/Core/Src/stm32f4xx_hal_msp.c @@ -24,6 +24,7 @@ /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ +extern DMA_HandleTypeDef hdma_adc1; /* Private typedef -----------------------------------------------------------*/ /* USER CODE BEGIN TD */ @@ -58,7 +59,9 @@ /* USER CODE BEGIN 0 */ /* USER CODE END 0 */ -/** + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); + /** * Initializes the Global MSP. */ void HAL_MspInit(void) @@ -77,6 +80,136 @@ void HAL_MspInit(void) /* USER CODE END MspInit 1 */ } +/** +* @brief ADC MSP Initialization +* This function configures the hardware resources used in this example +* @param hadc: ADC handle pointer +* @retval None +*/ +void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; + if(hadc->Instance==ADC1) + { + /* USER CODE BEGIN ADC1_MspInit 0 */ + + /* USER CODE END ADC1_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_ADC1_CLK_ENABLE(); + + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**ADC1 GPIO Configuration + PC5 ------> ADC1_IN15 + PB1 ------> ADC1_IN9 + */ + GPIO_InitStruct.Pin = I_Sense_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(I_Sense_GPIO_Port, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_1; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* ADC1 DMA Init */ + /* ADC1 Init */ + hdma_adc1.Instance = DMA2_Stream0; + hdma_adc1.Init.Channel = DMA_CHANNEL_0; + hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_adc1.Init.MemInc = DMA_MINC_ENABLE; + hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; + hdma_adc1.Init.Mode = DMA_NORMAL; + hdma_adc1.Init.Priority = DMA_PRIORITY_LOW; + hdma_adc1.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + if (HAL_DMA_Init(&hdma_adc1) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(hadc,DMA_Handle,hdma_adc1); + + /* USER CODE BEGIN ADC1_MspInit 1 */ + + /* USER CODE END ADC1_MspInit 1 */ + } + else if(hadc->Instance==ADC2) + { + /* USER CODE BEGIN ADC2_MspInit 0 */ + + /* USER CODE END ADC2_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_ADC2_CLK_ENABLE(); + + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**ADC2 GPIO Configuration + PB0 ------> ADC2_IN8 + */ + GPIO_InitStruct.Pin = I_SenseB0_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(I_SenseB0_GPIO_Port, &GPIO_InitStruct); + + /* USER CODE BEGIN ADC2_MspInit 1 */ + + /* USER CODE END ADC2_MspInit 1 */ + } + +} + +/** +* @brief ADC MSP De-Initialization +* This function freeze the hardware resources used in this example +* @param hadc: ADC handle pointer +* @retval None +*/ +void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc) +{ + if(hadc->Instance==ADC1) + { + /* USER CODE BEGIN ADC1_MspDeInit 0 */ + + /* USER CODE END ADC1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_ADC1_CLK_DISABLE(); + + /**ADC1 GPIO Configuration + PC5 ------> ADC1_IN15 + PB1 ------> ADC1_IN9 + */ + HAL_GPIO_DeInit(I_Sense_GPIO_Port, I_Sense_Pin); + + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_1); + + /* ADC1 DMA DeInit */ + HAL_DMA_DeInit(hadc->DMA_Handle); + /* USER CODE BEGIN ADC1_MspDeInit 1 */ + + /* USER CODE END ADC1_MspDeInit 1 */ + } + else if(hadc->Instance==ADC2) + { + /* USER CODE BEGIN ADC2_MspDeInit 0 */ + + /* USER CODE END ADC2_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_ADC2_CLK_DISABLE(); + + /**ADC2 GPIO Configuration + PB0 ------> ADC2_IN8 + */ + HAL_GPIO_DeInit(I_SenseB0_GPIO_Port, I_SenseB0_Pin); + + /* USER CODE BEGIN ADC2_MspDeInit 1 */ + + /* USER CODE END ADC2_MspDeInit 1 */ + } + +} + static uint32_t HAL_RCC_CAN1_CLK_ENABLED=0; /** @@ -139,6 +272,11 @@ void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan) GPIO_InitStruct.Alternate = GPIO_AF9_CAN2; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + /* CAN2 interrupt Init */ + HAL_NVIC_SetPriority(CAN2_RX0_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(CAN2_RX0_IRQn); + HAL_NVIC_SetPriority(CAN2_RX1_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(CAN2_RX1_IRQn); /* USER CODE BEGIN CAN2_MspInit 1 */ /* USER CODE END CAN2_MspInit 1 */ @@ -193,6 +331,9 @@ void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan) */ HAL_GPIO_DeInit(GPIOB, GPIO_PIN_12|GPIO_PIN_13); + /* CAN2 interrupt DeInit */ + HAL_NVIC_DisableIRQ(CAN2_RX0_IRQn); + HAL_NVIC_DisableIRQ(CAN2_RX1_IRQn); /* USER CODE BEGIN CAN2_MspDeInit 1 */ /* USER CODE END CAN2_MspDeInit 1 */ @@ -432,6 +573,144 @@ void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi) } +/** +* @brief TIM_Base MSP Initialization +* This function configures the hardware resources used in this example +* @param htim_base: TIM_Base handle pointer +* @retval None +*/ +void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) +{ + if(htim_base->Instance==TIM1) + { + /* USER CODE BEGIN TIM1_MspInit 0 */ + + /* USER CODE END TIM1_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM1_CLK_ENABLE(); + /* USER CODE BEGIN TIM1_MspInit 1 */ + + /* USER CODE END TIM1_MspInit 1 */ + } + else if(htim_base->Instance==TIM2) + { + /* USER CODE BEGIN TIM2_MspInit 0 */ + + /* USER CODE END TIM2_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM2_CLK_ENABLE(); + /* USER CODE BEGIN TIM2_MspInit 1 */ + + /* USER CODE END TIM2_MspInit 1 */ + } + else if(htim_base->Instance==TIM8) + { + /* USER CODE BEGIN TIM8_MspInit 0 */ + + /* USER CODE END TIM8_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM8_CLK_ENABLE(); + /* USER CODE BEGIN TIM8_MspInit 1 */ + + /* USER CODE END TIM8_MspInit 1 */ + } + +} + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; + if(htim->Instance==TIM1) + { + /* USER CODE BEGIN TIM1_MspPostInit 0 */ + + /* USER CODE END TIM1_MspPostInit 0 */ + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**TIM1 GPIO Configuration + PA8 ------> TIM1_CH1 + PA10 ------> TIM1_CH3 + */ + GPIO_InitStruct.Pin = Fan_PWMA8_Pin|Fan_PWMA10_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM1_MspPostInit 1 */ + + /* USER CODE END TIM1_MspPostInit 1 */ + } + else if(htim->Instance==TIM8) + { + /* USER CODE BEGIN TIM8_MspPostInit 0 */ + + /* USER CODE END TIM8_MspPostInit 0 */ + + __HAL_RCC_GPIOC_CLK_ENABLE(); + /**TIM8 GPIO Configuration + PC6 ------> TIM8_CH1 + PC7 ------> TIM8_CH2 + PC8 ------> TIM8_CH3 + PC9 ------> TIM8_CH4 + */ + GPIO_InitStruct.Pin = Fan_PWM_Pin|Fan_PWMC7_Pin|Fan_PWMC8_Pin|Fan_PWMC9_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF3_TIM8; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM8_MspPostInit 1 */ + + /* USER CODE END TIM8_MspPostInit 1 */ + } + +} +/** +* @brief TIM_Base MSP De-Initialization +* This function freeze the hardware resources used in this example +* @param htim_base: TIM_Base handle pointer +* @retval None +*/ +void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base) +{ + if(htim_base->Instance==TIM1) + { + /* USER CODE BEGIN TIM1_MspDeInit 0 */ + + /* USER CODE END TIM1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM1_CLK_DISABLE(); + /* USER CODE BEGIN TIM1_MspDeInit 1 */ + + /* USER CODE END TIM1_MspDeInit 1 */ + } + else if(htim_base->Instance==TIM2) + { + /* USER CODE BEGIN TIM2_MspDeInit 0 */ + + /* USER CODE END TIM2_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM2_CLK_DISABLE(); + /* USER CODE BEGIN TIM2_MspDeInit 1 */ + + /* USER CODE END TIM2_MspDeInit 1 */ + } + else if(htim_base->Instance==TIM8) + { + /* USER CODE BEGIN TIM8_MspDeInit 0 */ + + /* USER CODE END TIM8_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM8_CLK_DISABLE(); + /* USER CODE BEGIN TIM8_MspDeInit 1 */ + + /* USER CODE END TIM8_MspDeInit 1 */ + } + +} + /** * @brief UART MSP Initialization * This function configures the hardware resources used in this example diff --git a/Core/Src/stm32f4xx_it.c b/Core/Src/stm32f4xx_it.c index 2ae44d9..bd9e3ce 100644 --- a/Core/Src/stm32f4xx_it.c +++ b/Core/Src/stm32f4xx_it.c @@ -22,6 +22,7 @@ #include "stm32f4xx_it.h" /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ +#include "can_handler.h" /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ @@ -55,7 +56,8 @@ /* USER CODE END 0 */ /* External variables --------------------------------------------------------*/ - +extern DMA_HandleTypeDef hdma_adc1; +extern CAN_HandleTypeDef hcan2; /* USER CODE BEGIN EV */ /* USER CODE END EV */ @@ -198,6 +200,48 @@ void SysTick_Handler(void) /* please refer to the startup file (startup_stm32f4xx.s). */ /******************************************************************************/ +/** + * @brief This function handles DMA2 stream0 global interrupt. + */ +void DMA2_Stream0_IRQHandler(void) +{ + /* USER CODE BEGIN DMA2_Stream0_IRQn 0 */ + + /* USER CODE END DMA2_Stream0_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_adc1); + /* USER CODE BEGIN DMA2_Stream0_IRQn 1 */ + + /* USER CODE END DMA2_Stream0_IRQn 1 */ +} + +/** + * @brief This function handles CAN2 RX0 interrupts. + */ +void CAN2_RX0_IRQHandler(void) +{ + /* USER CODE BEGIN CAN2_RX0_IRQn 0 */ + can_receive_callback(&hcan2); + /* USER CODE END CAN2_RX0_IRQn 0 */ + HAL_CAN_IRQHandler(&hcan2); + /* USER CODE BEGIN CAN2_RX0_IRQn 1 */ + + /* USER CODE END CAN2_RX0_IRQn 1 */ +} + +/** + * @brief This function handles CAN2 RX1 interrupt. + */ +void CAN2_RX1_IRQHandler(void) +{ + /* USER CODE BEGIN CAN2_RX1_IRQn 0 */ + can_receive_callback(&hcan2); + /* USER CODE END CAN2_RX1_IRQn 0 */ + HAL_CAN_IRQHandler(&hcan2); + /* USER CODE BEGIN CAN2_RX1_IRQn 1 */ + + /* USER CODE END CAN2_RX1_IRQn 1 */ +} + /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ diff --git a/Dockerfile b/Dockerfile deleted file mode 100644 index 976b5f3..0000000 --- a/Dockerfile +++ /dev/null @@ -1,49 +0,0 @@ -FROM ubuntu:latest - -# Set up container and time zones -RUN apt-get update && \ - DEBIAN_FRONTEND=noninteractive TZ="America/New_York" \ - apt-get -y install tzdata - -# Download Linux support tools -RUN apt-get install -y \ - build-essential \ - wget \ - curl \ - openocd \ - git \ - gdb-multiarch \ - minicom \ - vim - -RUN wget https://builds.renode.io/renode-1.13.3+20230712gitedfc975b.linux-portable.tar.gz -RUN mkdir renode_portable && tar -xvf renode-*.linux-portable.tar.gz -C renode_portable --strip-components=1 -ENV PATH $PATH:/renode_portable - -# Set up a development tools directory -WORKDIR /home/dev -ADD . /home/dev - -RUN echo 'if [ $n -e /home/app/shepherd2.ioc ]; then echo \ -" ______ __ __ ______ ______ __ __ ______ ______ _____\n\ -/\ ___\ /\ \_\ \ /\ ___\ /\ == \ /\ \_\ \ /\ ___\ /\ == \ /\ __-.\n\ -\ \___ \ \ \ __ \ \ \ __\ \ \ _-/ \ \ __ \ \ \ __\ \ \ __< \ \ \/\ \ \n\ - \/\_____\ \ \_\ \_\ \ \_____\ \ \_\ \ \_\ \_\ \ \_____\ \ \_\ \_\ \ \____- \n\ - \/_____/ \/_/\/_/ \/_____/ \/_/ \/_/\/_/ \/_____/ \/_/ /_/ \/____/"; fi;' >> ~/.bashrc && \ -echo 'if [ $n -e /home/app/cerberus.ioc ]; then echo \ -"_________ ___. \n\ -\_ ___ \ __________\_ |__ ___________ __ __ ______\n\ -/ \ \/_/ __ \_ __ \ __ \_/ __ \_ __ \ | \/ ___/\n\ -\ \___\ ___/| | \/ \_\ \ ___/| | \/ | /\___ \ \n\ - \______ /\___ >__| |___ /\___ >__| |____//____ >\n\ - \/ \/ \/ \/ \/ "; fi;' >> ~/.bashrc \ -&& echo 'alias serial="minicom -b 115200 -o -D /dev/ttyACM0"' >> ~/.bashrc \ -&& echo 'alias flash="openocd -f interface/cmsis-dap.cfg -f target/stm32f4x.cfg -c \"adapter speed 5000\" -c \"program /home/app/build/cerberus.elf verify reset exit\""' >> ~/.bashrc \ -&& echo 'alias emulate="renode /home/app/*.resc"' >> ~/.bashrc - -# Install cross compiler -RUN wget -qO- https://developer.arm.com/-/media/Files/downloads/gnu-rm/10.3-2021.10/gcc-arm-none-eabi-10.3-2021.10-x86_64-linux.tar.bz2 | tar -xvj - -ENV PATH $PATH:/home/dev/gcc-arm-none-eabi-10.3-2021.10/bin - -WORKDIR /home/app diff --git a/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f405xx.h b/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f405xx.h index 076b20b..1ab62e7 100644 --- a/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f405xx.h +++ b/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f405xx.h @@ -1,14310 +1,14310 @@ -/** - ****************************************************************************** - * @file stm32f405xx.h - * @author MCD Application Team - * @brief CMSIS STM32F405xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - peripherals registers declarations and bits definition - * - Macros to access peripheral’s registers hardware - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32f405xx - * @{ - */ - -#ifndef __STM32F405xx_H -#define __STM32F405xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1U /*!< FPU present */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F4XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare global interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - RNG_IRQn = 80, /*!< RNG global Interrupt */ - FPU_IRQn = 81 /*!< FPU global interrupt */ -} IRQn_Type; -/* Legacy define */ -#define HASH_RNG_IRQn RNG_IRQn - -/** - * @} - */ - -#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ -#include "system_stm32f4xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ - __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ -} FLASH_TypeDef; - - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ - uint32_t RESERVED1; /*!< Reserved, 0x78 */ - uint32_t RESERVED2; /*!< Reserved, 0x7C */ - __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED3; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FSMC_Bank2_3_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank4 - */ - -typedef struct -{ - __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ - __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ - __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ - __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ - __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ -} FSMC_Bank4_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - uint32_t Reserved40[48]; /*!< Reserved 0x40-0xFF */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define FLASH_BASE 0x08000000UL /*!< FLASH(up to 1 MB) base address in the alias region */ -#define CCMDATARAM_BASE 0x10000000UL /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region */ -#define SRAM1_BASE 0x20000000UL /*!< SRAM1(112 KB) base address in the alias region */ -#define SRAM2_BASE 0x2001C000UL /*!< SRAM2(16 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000UL /*!< Peripheral base address in the alias region */ -#define BKPSRAM_BASE 0x40024000UL /*!< Backup SRAM(4 KB) base address in the alias region */ -#define FSMC_R_BASE 0xA0000000UL /*!< FSMC registers base address */ -#define SRAM1_BB_BASE 0x22000000UL /*!< SRAM1(112 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22380000UL /*!< SRAM2(16 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000UL /*!< Peripheral base address in the bit-band region */ -#define BKPSRAM_BB_BASE 0x42480000UL /*!< Backup SRAM(4 KB) base address in the bit-band region */ -#define FLASH_END 0x080FFFFFUL /*!< FLASH end address */ -#define FLASH_OTP_BASE 0x1FFF7800UL /*!< Base address of : (up to 528 Bytes) embedded FLASH OTP Area */ -#define FLASH_OTP_END 0x1FFF7A0FUL /*!< End address of : (up to 528 Bytes) embedded FLASH OTP Area */ -#define CCMDATARAM_END 0x1000FFFFUL /*!< CCM data RAM end address */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000UL) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000UL) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400UL) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00UL) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400UL) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800UL) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400UL) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400UL) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000UL) -#define ADC2_BASE (APB2PERIPH_BASE + 0x2100UL) -#define ADC3_BASE (APB2PERIPH_BASE + 0x2200UL) -#define ADC123_COMMON_BASE (APB2PERIPH_BASE + 0x2300UL) -/* Legacy define */ -#define ADC_BASE ADC123_COMMON_BASE -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00UL) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800UL) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00UL) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000UL) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400UL) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800UL) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00UL) -#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000UL) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800UL) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00UL) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000UL) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400UL) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800UL) - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000UL) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104UL) -#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060UL) -#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0UL) - - -/*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000UL -/*!< USB registers base address */ -#define USB_OTG_HS_PERIPH_BASE 0x40040000UL -#define USB_OTG_FS_PERIPH_BASE 0x50000000UL - -#define USB_OTG_GLOBAL_BASE 0x000UL -#define USB_OTG_DEVICE_BASE 0x800UL -#define USB_OTG_IN_ENDPOINT_BASE 0x900UL -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00UL -#define USB_OTG_EP_REG_SIZE 0x20UL -#define USB_OTG_HOST_BASE 0x400UL -#define USB_OTG_HOST_PORT_BASE 0x440UL -#define USB_OTG_HOST_CHANNEL_BASE 0x500UL -#define USB_OTG_HOST_CHANNEL_SIZE 0x20UL -#define USB_OTG_PCGCCTL_BASE 0xE00UL -#define USB_OTG_FIFO_BASE 0x1000UL -#define USB_OTG_FIFO_SIZE 0x1000UL - -#define UID_BASE 0x1FFF7A10UL /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22UL /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0UL /*!< Package size register base address */ -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define ADC123_COMMON ((ADC_Common_TypeDef *) ADC123_COMMON_BASE) -/* Legacy define */ -#define ADC ADC123_COMMON -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) -#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) -#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - -/** @addtogroup Hardware_Constant_Definition - * @{ - */ -#define LSI_STARTUP_TIME 40U /*!< LSI Maximum startup time in us */ -/** - * @} - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/* - * @brief Specific device feature definitions (not present on all devices in the STM32F4 serie) - */ -#define ADC_MULTIMODE_SUPPORT /*! + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ + __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ + __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ + __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ + __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ + __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ + __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ + __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + __IO uint32_t TDLR; /*!< CAN mailbox data low register */ + __IO uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ + __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CAN_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA stream x configuration register */ + __IO uint32_t NDTR; /*!< DMA stream x number of data register */ + __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ + __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ + __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ + __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ +} DMA_Stream_TypeDef; + +typedef struct +{ + __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ + __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ + __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ + __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ +} DMA_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ + __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ + __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ + __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ + __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ + __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ + __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ + __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ +} FLASH_TypeDef; + + + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ + uint32_t RESERVED1; /*!< Reserved, 0x78 */ + uint32_t RESERVED2; /*!< Reserved, 0x7C */ + __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED3; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FSMC_Bank2_3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ + __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ + __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ + __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ + __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ +} FSMC_Bank4_TypeDef; + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ +} GPIO_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ + __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ +} SYSCFG_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ + __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ + __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ + __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ + __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ + __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ +} IWDG_TypeDef; + + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ + __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved, 0x3C */ + __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ + uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, 0x5C */ + __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ + uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ + __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ + __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ + __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ + __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ + __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ + __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ + __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ + __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ + __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ + uint32_t RESERVED7; /*!< Reserved, 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ + __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ + __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ + __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ + __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ + __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ + __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ + __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ + __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ + __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ + __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ + __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ + __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ + __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ + __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ + __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ + __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ + __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ + __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ + __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ +} RTC_TypeDef; + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ + __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ + __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ + __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ + __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ + __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ + __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ + __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ + __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ + uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ + __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ + __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ + __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ + __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ + __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ + __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ + __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ +} SPI_TypeDef; + + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ + __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ + __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ + __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + +/** + * @brief RNG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + +/** + * @brief USB_OTG_Core_Registers + */ +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ + __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ + __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ + uint32_t Reserved30[2]; /*!< Reserved 030h */ + __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ + __IO uint32_t CID; /*!< User ID Register 03Ch */ + uint32_t Reserved40[48]; /*!< Reserved 0x40-0xFF */ + __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ + __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ +} USB_OTG_GlobalTypeDef; + +/** + * @brief USB_OTG_device_Registers + */ +typedef struct +{ + __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ + __IO uint32_t DCTL; /*!< dev Control Register 804h */ + __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ + uint32_t Reserved0C; /*!< Reserved 80Ch */ + __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ + __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ + __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ + __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ + uint32_t Reserved20; /*!< Reserved 820h */ + uint32_t Reserved9; /*!< Reserved 824h */ + __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ + __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ + __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ + __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ + __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ + __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ + uint32_t Reserved40; /*!< dedicated EP mask 840h */ + __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ + uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ + __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ +} USB_OTG_DeviceTypeDef; + +/** + * @brief USB_OTG_IN_Endpoint-Specific_Register + */ +typedef struct +{ + __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ + __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ + __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ + __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ + __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ + uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ +} USB_OTG_INEndpointTypeDef; + +/** + * @brief USB_OTG_OUT_Endpoint-Specific_Registers + */ +typedef struct +{ + __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ + __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ + __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ + __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ + uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ +} USB_OTG_OUTEndpointTypeDef; + +/** + * @brief USB_OTG_Host_Mode_Register_Structures + */ +typedef struct +{ + __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ + __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ + __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ + uint32_t Reserved40C; /*!< Reserved 40Ch */ + __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ + __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ + __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ +} USB_OTG_HostTypeDef; + +/** + * @brief USB_OTG_Host_Channel_Specific_Registers + */ +typedef struct +{ + __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ + __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ + __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ + __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ + __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ + __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ + uint32_t Reserved[2]; /*!< Reserved */ +} USB_OTG_HostChannelTypeDef; + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ +#define FLASH_BASE 0x08000000UL /*!< FLASH(up to 1 MB) base address in the alias region */ +#define CCMDATARAM_BASE 0x10000000UL /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region */ +#define SRAM1_BASE 0x20000000UL /*!< SRAM1(112 KB) base address in the alias region */ +#define SRAM2_BASE 0x2001C000UL /*!< SRAM2(16 KB) base address in the alias region */ +#define PERIPH_BASE 0x40000000UL /*!< Peripheral base address in the alias region */ +#define BKPSRAM_BASE 0x40024000UL /*!< Backup SRAM(4 KB) base address in the alias region */ +#define FSMC_R_BASE 0xA0000000UL /*!< FSMC registers base address */ +#define SRAM1_BB_BASE 0x22000000UL /*!< SRAM1(112 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE 0x22380000UL /*!< SRAM2(16 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE 0x42000000UL /*!< Peripheral base address in the bit-band region */ +#define BKPSRAM_BB_BASE 0x42480000UL /*!< Backup SRAM(4 KB) base address in the bit-band region */ +#define FLASH_END 0x080FFFFFUL /*!< FLASH end address */ +#define FLASH_OTP_BASE 0x1FFF7800UL /*!< Base address of : (up to 528 Bytes) embedded FLASH OTP Area */ +#define FLASH_OTP_END 0x1FFF7A0FUL /*!< End address of : (up to 528 Bytes) embedded FLASH OTP Area */ +#define CCMDATARAM_END 0x1000FFFFUL /*!< CCM data RAM end address */ + +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000UL) + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00UL) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800UL) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00UL) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000UL) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) +#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400UL) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) +#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000UL) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000UL) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00UL) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400UL) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800UL) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400UL) + +/*!< APB2 peripherals */ +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000UL) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400UL) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000UL) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400UL) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000UL) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100UL) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200UL) +#define ADC123_COMMON_BASE (APB2PERIPH_BASE + 0x2300UL) +/* Legacy define */ +#define ADC_BASE ADC123_COMMON_BASE +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00UL) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800UL) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00UL) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000UL) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400UL) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800UL) + +/*!< AHB1 peripherals */ +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000UL) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400UL) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800UL) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00UL) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000UL) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400UL) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800UL) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00UL) +#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000UL) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800UL) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00UL) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000UL) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400UL) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) + +/*!< AHB2 peripherals */ +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800UL) + +/*!< FSMC Bankx registers base address */ +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000UL) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104UL) +#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060UL) +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0UL) + + +/*!< Debug MCU registers base address */ +#define DBGMCU_BASE 0xE0042000UL +/*!< USB registers base address */ +#define USB_OTG_HS_PERIPH_BASE 0x40040000UL +#define USB_OTG_FS_PERIPH_BASE 0x50000000UL + +#define USB_OTG_GLOBAL_BASE 0x000UL +#define USB_OTG_DEVICE_BASE 0x800UL +#define USB_OTG_IN_ENDPOINT_BASE 0x900UL +#define USB_OTG_OUT_ENDPOINT_BASE 0xB00UL +#define USB_OTG_EP_REG_SIZE 0x20UL +#define USB_OTG_HOST_BASE 0x400UL +#define USB_OTG_HOST_PORT_BASE 0x440UL +#define USB_OTG_HOST_CHANNEL_BASE 0x500UL +#define USB_OTG_HOST_CHANNEL_SIZE 0x20UL +#define USB_OTG_PCGCCTL_BASE 0xE00UL +#define USB_OTG_FIFO_BASE 0x1000UL +#define USB_OTG_FIFO_SIZE 0x1000UL + +#define UID_BASE 0x1FFF7A10UL /*!< Unique device ID register base address */ +#define FLASHSIZE_BASE 0x1FFF7A22UL /*!< FLASH Size register base address */ +#define PACKAGE_BASE 0x1FFF7BF0UL /*!< Package size register base address */ +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC1 ((DAC_TypeDef *) DAC_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define ADC123_COMMON ((ADC_Common_TypeDef *) ADC123_COMMON_BASE) +/* Legacy define */ +#define ADC ADC123_COMMON +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) +#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) +#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) +#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) +#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) +#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) +#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) +#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) +#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) +#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) +#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) +#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) +#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) +#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) +#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) +#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) +#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) +#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + +/** @addtogroup Hardware_Constant_Definition + * @{ + */ +#define LSI_STARTUP_TIME 40U /*!< LSI Maximum startup time in us */ +/** + * @} + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/* + * @brief Specific device feature definitions (not present on all devices in the STM32F4 serie) + */ +#define ADC_MULTIMODE_SUPPORT /*!>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ - return result; -} -#endif - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) -#else - #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) -#else - #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) -#else - #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXB(value, ptr) __strex(value, ptr) -#else - #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXH(value, ptr) __strex(value, ptr) -#else - #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXW(value, ptr) __strex(value, ptr) -#else - #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __clrex - - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) -{ - rrx r0, r0 - bx lr -} -#endif - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRBT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRHT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRT(value, ptr) __strt(value, ptr) - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -#define __SADD8 __sadd8 -#define __QADD8 __qadd8 -#define __SHADD8 __shadd8 -#define __UADD8 __uadd8 -#define __UQADD8 __uqadd8 -#define __UHADD8 __uhadd8 -#define __SSUB8 __ssub8 -#define __QSUB8 __qsub8 -#define __SHSUB8 __shsub8 -#define __USUB8 __usub8 -#define __UQSUB8 __uqsub8 -#define __UHSUB8 __uhsub8 -#define __SADD16 __sadd16 -#define __QADD16 __qadd16 -#define __SHADD16 __shadd16 -#define __UADD16 __uadd16 -#define __UQADD16 __uqadd16 -#define __UHADD16 __uhadd16 -#define __SSUB16 __ssub16 -#define __QSUB16 __qsub16 -#define __SHSUB16 __shsub16 -#define __USUB16 __usub16 -#define __UQSUB16 __uqsub16 -#define __UHSUB16 __uhsub16 -#define __SASX __sasx -#define __QASX __qasx -#define __SHASX __shasx -#define __UASX __uasx -#define __UQASX __uqasx -#define __UHASX __uhasx -#define __SSAX __ssax -#define __QSAX __qsax -#define __SHSAX __shsax -#define __USAX __usax -#define __UQSAX __uqsax -#define __UHSAX __uhsax -#define __USAD8 __usad8 -#define __USADA8 __usada8 -#define __SSAT16 __ssat16 -#define __USAT16 __usat16 -#define __UXTB16 __uxtb16 -#define __UXTAB16 __uxtab16 -#define __SXTB16 __sxtb16 -#define __SXTAB16 __sxtab16 -#define __SMUAD __smuad -#define __SMUADX __smuadx -#define __SMLAD __smlad -#define __SMLADX __smladx -#define __SMLALD __smlald -#define __SMLALDX __smlaldx -#define __SMUSD __smusd -#define __SMUSDX __smusdx -#define __SMLSD __smlsd -#define __SMLSDX __smlsdx -#define __SMLSLD __smlsld -#define __SMLSLDX __smlsldx -#define __SEL __sel -#define __QADD __qadd -#define __QSUB __qsub - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ - ((int64_t)(ARG3) << 32U) ) >> 32U)) - -#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCC_H */ +/**************************************************************************//** + * @file cmsis_armcc.h + * @brief CMSIS compiler ARMCC (Arm Compiler 5) header file + * @version V5.0.4 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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 __CMSIS_ARMCC_H +#define __CMSIS_ARMCC_H + + +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677) + #error "Please use Arm Compiler Toolchain V4.0.677 or later!" +#endif + +/* CMSIS compiler control architecture macros */ +#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \ + (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) ) + #define __ARM_ARCH_6M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1)) + #define __ARM_ARCH_7M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1)) + #define __ARM_ARCH_7EM__ 1 +#endif + + /* __ARM_ARCH_8M_BASE__ not applicable */ + /* __ARM_ARCH_8M_MAIN__ not applicable */ + + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE static __forceinline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __declspec(noreturn) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed)) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT __packed struct +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION __packed union +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x))) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr))) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr))) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); */ + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xFFU); +} + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + register uint32_t __regBasePriMax __ASM("basepri_max"); + __regBasePriMax = (basePri & 0xFFU); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1U); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +#define __ISB() do {\ + __schedule_barrier();\ + __isb(0xF);\ + __schedule_barrier();\ + } while (0U) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() do {\ + __schedule_barrier();\ + __dsb(0xF);\ + __schedule_barrier();\ + } while (0U) + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() do {\ + __schedule_barrier();\ + __dmb(0xF);\ + __schedule_barrier();\ + } while (0U) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} +#endif + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} +#endif + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +#define __ROR __ror + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __breakpoint(value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + #define __RBIT __rbit +#else +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ + return result; +} +#endif + + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) +#else + #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) +#else + #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) +#else + #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXB(value, ptr) __strex(value, ptr) +#else + #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXH(value, ptr) __strex(value, ptr) +#else + #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXW(value, ptr) __strex(value, ptr) +#else + #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __clrex + + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) +{ + rrx r0, r0 + bx lr +} +#endif + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRBT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRHT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRT(value, ptr) __strt(value, ptr) + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +#define __SADD8 __sadd8 +#define __QADD8 __qadd8 +#define __SHADD8 __shadd8 +#define __UADD8 __uadd8 +#define __UQADD8 __uqadd8 +#define __UHADD8 __uhadd8 +#define __SSUB8 __ssub8 +#define __QSUB8 __qsub8 +#define __SHSUB8 __shsub8 +#define __USUB8 __usub8 +#define __UQSUB8 __uqsub8 +#define __UHSUB8 __uhsub8 +#define __SADD16 __sadd16 +#define __QADD16 __qadd16 +#define __SHADD16 __shadd16 +#define __UADD16 __uadd16 +#define __UQADD16 __uqadd16 +#define __UHADD16 __uhadd16 +#define __SSUB16 __ssub16 +#define __QSUB16 __qsub16 +#define __SHSUB16 __shsub16 +#define __USUB16 __usub16 +#define __UQSUB16 __uqsub16 +#define __UHSUB16 __uhsub16 +#define __SASX __sasx +#define __QASX __qasx +#define __SHASX __shasx +#define __UASX __uasx +#define __UQASX __uqasx +#define __UHASX __uhasx +#define __SSAX __ssax +#define __QSAX __qsax +#define __SHSAX __shsax +#define __USAX __usax +#define __UQSAX __uqsax +#define __UHSAX __uhsax +#define __USAD8 __usad8 +#define __USADA8 __usada8 +#define __SSAT16 __ssat16 +#define __USAT16 __usat16 +#define __UXTB16 __uxtb16 +#define __UXTAB16 __uxtab16 +#define __SXTB16 __sxtb16 +#define __SXTAB16 __sxtab16 +#define __SMUAD __smuad +#define __SMUADX __smuadx +#define __SMLAD __smlad +#define __SMLADX __smladx +#define __SMLALD __smlald +#define __SMLALDX __smlaldx +#define __SMUSD __smusd +#define __SMUSDX __smusdx +#define __SMLSD __smlsd +#define __SMLSDX __smlsdx +#define __SMLSLD __smlsld +#define __SMLSLDX __smlsldx +#define __SEL __sel +#define __QADD __qadd +#define __QSUB __qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ + ((int64_t)(ARG3) << 32U) ) >> 32U)) + +#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCC_H */ diff --git a/Drivers/CMSIS/Include/cmsis_armclang.h b/Drivers/CMSIS/Include/cmsis_armclang.h index 162a400..d8031b0 100644 --- a/Drivers/CMSIS/Include/cmsis_armclang.h +++ b/Drivers/CMSIS/Include/cmsis_armclang.h @@ -1,1869 +1,1869 @@ -/**************************************************************************//** - * @file cmsis_armclang.h - * @brief CMSIS compiler armclang (Arm Compiler 6) header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ - -#ifndef __CMSIS_ARMCLANG_H -#define __CMSIS_ARMCLANG_H - -#pragma clang system_header /* treat file as system include file */ - -#ifndef __ARM_COMPAT_H -#include /* Compatibility header for Arm Compiler 5 intrinsics */ -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE __inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static __inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __enable_irq(); see arm_compat.h */ - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __disable_irq(); see arm_compat.h */ - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr -#else -#define __get_FPSCR() ((uint32_t)0U) -#endif - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __set_FPSCR __builtin_arm_set_fpscr -#else -#define __set_FPSCR(x) ((void)(x)) -#endif - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __builtin_arm_nop - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __builtin_arm_wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __builtin_arm_wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __builtin_arm_sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() __builtin_arm_isb(0xF); - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __builtin_arm_dsb(0xF); - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __builtin_arm_dmb(0xF); - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV(value) __builtin_bswap32(value) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV16(value) __ROR(__REV(value), 16) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REVSH(value) (int16_t)__builtin_bswap16(value) - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -#define __RBIT __builtin_arm_rbit - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB (uint8_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH (uint16_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW (uint32_t)__builtin_arm_ldrex - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW (uint32_t)__builtin_arm_strex - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __builtin_arm_clrex - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __builtin_arm_ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __builtin_arm_usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDAEXB (uint8_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDAEXH (uint16_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDAEX (uint32_t)__builtin_arm_ldaex - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXB (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXH (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEX (uint32_t)__builtin_arm_stlex - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCLANG_H */ +/**************************************************************************//** + * @file cmsis_armclang.h + * @brief CMSIS compiler armclang (Arm Compiler 6) header file + * @version V5.0.4 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ + +#ifndef __CMSIS_ARMCLANG_H +#define __CMSIS_ARMCLANG_H + +#pragma clang system_header /* treat file as system include file */ + +#ifndef __ARM_COMPAT_H +#include /* Compatibility header for Arm Compiler 5 intrinsics */ +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); see arm_compat.h */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); see arm_compat.h */ + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr +#else +#define __get_FPSCR() ((uint32_t)0U) +#endif + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __set_FPSCR __builtin_arm_set_fpscr +#else +#define __set_FPSCR(x) ((void)(x)) +#endif + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __builtin_arm_nop + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __builtin_arm_wfi + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __builtin_arm_wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __builtin_arm_sev + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +#define __ISB() __builtin_arm_isb(0xF); + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __builtin_arm_dsb(0xF); + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __builtin_arm_dmb(0xF); + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV(value) __builtin_bswap32(value) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV16(value) __ROR(__REV(value), 16) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REVSH(value) (int16_t)__builtin_bswap16(value) + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __builtin_arm_rbit + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ (uint8_t)__builtin_clz + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB (uint8_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH (uint16_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW (uint32_t)__builtin_arm_ldrex + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW (uint32_t)__builtin_arm_strex + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __builtin_arm_clrex + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __builtin_arm_ssat + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __builtin_arm_usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDAEXB (uint8_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDAEXH (uint16_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDAEX (uint32_t)__builtin_arm_ldaex + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXB (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXH (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEX (uint32_t)__builtin_arm_stlex + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#if 0 +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) +#endif + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCLANG_H */ diff --git a/Drivers/CMSIS/Include/cmsis_compiler.h b/Drivers/CMSIS/Include/cmsis_compiler.h index 94212eb..79a2cac 100644 --- a/Drivers/CMSIS/Include/cmsis_compiler.h +++ b/Drivers/CMSIS/Include/cmsis_compiler.h @@ -1,266 +1,266 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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 __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - +/**************************************************************************//** + * @file cmsis_compiler.h + * @brief CMSIS compiler generic header file + * @version V5.0.4 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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 __CMSIS_COMPILER_H +#define __CMSIS_COMPILER_H + +#include + +/* + * Arm Compiler 4/5 + */ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + + +/* + * Arm Compiler 6 (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #include "cmsis_armclang.h" + + +/* + * GNU Compiler + */ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + + +/* + * IAR Compiler + */ +#elif defined ( __ICCARM__ ) + #include + + +/* + * TI Arm Compiler + */ +#elif defined ( __TI_ARM__ ) + #include + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __attribute__((packed)) + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed)) + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed)) + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +/* + * TASKING Compiler + */ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __packed__ + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __packed__ + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __packed__ + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __packed__ T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __align(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +/* + * COSMIC Compiler + */ +#elif defined ( __CSMC__ ) + #include + + #ifndef __ASM + #define __ASM _asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + // NO RETURN is automatically detected hence no warning here + #define __NO_RETURN + #endif + #ifndef __USED + #warning No compiler specific solution for __USED. __USED is ignored. + #define __USED + #endif + #ifndef __WEAK + #define __WEAK __weak + #endif + #ifndef __PACKED + #define __PACKED @packed + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT @packed struct + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION @packed union + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + @packed struct T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. + #define __ALIGNED(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +#else + #error Unknown compiler. +#endif + + +#endif /* __CMSIS_COMPILER_H */ + diff --git a/Drivers/CMSIS/Include/cmsis_gcc.h b/Drivers/CMSIS/Include/cmsis_gcc.h index 2d9db15..1bd41a4 100644 --- a/Drivers/CMSIS/Include/cmsis_gcc.h +++ b/Drivers/CMSIS/Include/cmsis_gcc.h @@ -1,2085 +1,2085 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.0.4 - * @date 09. April 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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 __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ +/**************************************************************************//** + * @file cmsis_gcc.h + * @brief CMSIS compiler GCC header file + * @version V5.0.4 + * @date 09. April 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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 __CMSIS_GCC_H +#define __CMSIS_GCC_H + +/* ignore some GCC warnings */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wsign-conversion" +#pragma GCC diagnostic ignored "-Wconversion" +#pragma GCC diagnostic ignored "-Wunused-parameter" + +/* Fallback for __has_builtin */ +#ifndef __has_builtin + #define __has_builtin(x) (0) +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i" : : : "memory"); +} + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i" : : : "memory"); +} + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f" : : : "memory"); +} + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f" : : : "memory"); +} + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_get_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + return __builtin_arm_get_fpscr(); +#else + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#endif +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_set_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + __builtin_arm_set_fpscr(fpscr); +#else + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); +#endif +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_RW_REG(r) "+l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_RW_REG(r) "+r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP() __ASM volatile ("nop") + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI() __ASM volatile ("wfi") + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE() __ASM volatile ("wfe") + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV() __ASM volatile ("sev") + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +__STATIC_FORCEINLINE void __ISB(void) +{ + __ASM volatile ("isb 0xF":::"memory"); +} + + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__STATIC_FORCEINLINE void __DSB(void) +{ + __ASM volatile ("dsb 0xF":::"memory"); +} + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__STATIC_FORCEINLINE void __DMB(void) +{ + __ASM volatile ("dmb 0xF":::"memory"); +} + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else + uint32_t result; + + __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (int16_t)__builtin_bswap16(value); +#else + int16_t result; + + __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); +#else + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ +#endif + return result; +} + + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ (uint8_t)__builtin_clz + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); + return(result); +} + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +__STATIC_FORCEINLINE void __CLREX(void) +{ + __ASM volatile ("clrex" ::: "memory"); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +__extension__ \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ + __extension__ \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); + return(result); +} + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#if 0 +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) +#endif + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#pragma GCC diagnostic pop + +#endif /* __CMSIS_GCC_H */ diff --git a/Drivers/CMSIS/Include/cmsis_iccarm.h b/Drivers/CMSIS/Include/cmsis_iccarm.h index 11c4af0..3c90a2c 100644 --- a/Drivers/CMSIS/Include/cmsis_iccarm.h +++ b/Drivers/CMSIS/Include/cmsis_iccarm.h @@ -1,935 +1,935 @@ -/**************************************************************************//** - * @file cmsis_iccarm.h - * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file - * @version V5.0.7 - * @date 19. June 2018 - ******************************************************************************/ - -//------------------------------------------------------------------------------ -// -// Copyright (c) 2017-2018 IAR Systems -// -// Licensed 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 __CMSIS_ICCARM_H__ -#define __CMSIS_ICCARM_H__ - -#ifndef __ICCARM__ - #error This file should only be compiled by ICCARM -#endif - -#pragma system_include - -#define __IAR_FT _Pragma("inline=forced") __intrinsic - -#if (__VER__ >= 8000000) - #define __ICCARM_V8 1 -#else - #define __ICCARM_V8 0 -#endif - -#ifndef __ALIGNED - #if __ICCARM_V8 - #define __ALIGNED(x) __attribute__((aligned(x))) - #elif (__VER__ >= 7080000) - /* Needs IAR language extensions */ - #define __ALIGNED(x) __attribute__((aligned(x))) - #else - #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. - #define __ALIGNED(x) - #endif -#endif - - -/* Define compiler macros for CPU architecture, used in CMSIS 5. - */ -#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ -/* Macros already defined */ -#else - #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' - #if __ARM_ARCH == 6 - #define __ARM_ARCH_6M__ 1 - #elif __ARM_ARCH == 7 - #if __ARM_FEATURE_DSP - #define __ARM_ARCH_7EM__ 1 - #else - #define __ARM_ARCH_7M__ 1 - #endif - #endif /* __ARM_ARCH */ - #endif /* __ARM_ARCH_PROFILE == 'M' */ -#endif - -/* Alternativ core deduction for older ICCARM's */ -#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ - !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) - #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) - #define __ARM_ARCH_6M__ 1 - #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) - #define __ARM_ARCH_7M__ 1 - #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) - #define __ARM_ARCH_7EM__ 1 - #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #else - #error "Unknown target." - #endif -#endif - - - -#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 - #define __IAR_M0_FAMILY 1 -#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 - #define __IAR_M0_FAMILY 1 -#else - #define __IAR_M0_FAMILY 0 -#endif - - -#ifndef __ASM - #define __ASM __asm -#endif - -#ifndef __INLINE - #define __INLINE inline -#endif - -#ifndef __NO_RETURN - #if __ICCARM_V8 - #define __NO_RETURN __attribute__((__noreturn__)) - #else - #define __NO_RETURN _Pragma("object_attribute=__noreturn") - #endif -#endif - -#ifndef __PACKED - #if __ICCARM_V8 - #define __PACKED __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED __packed - #endif -#endif - -#ifndef __PACKED_STRUCT - #if __ICCARM_V8 - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_STRUCT __packed struct - #endif -#endif - -#ifndef __PACKED_UNION - #if __ICCARM_V8 - #define __PACKED_UNION union __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_UNION __packed union - #endif -#endif - -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif - -#ifndef __FORCEINLINE - #define __FORCEINLINE _Pragma("inline=forced") -#endif - -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE -#endif - -#ifndef __UNALIGNED_UINT16_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint16_t __iar_uint16_read(void const *ptr) -{ - return *(__packed uint16_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) -#endif - - -#ifndef __UNALIGNED_UINT16_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) -{ - *(__packed uint16_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint32_t __iar_uint32_read(void const *ptr) -{ - return *(__packed uint32_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) -#endif - -#ifndef __UNALIGNED_UINT32_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) -{ - *(__packed uint32_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32 /* deprecated */ -#pragma language=save -#pragma language=extended -__packed struct __iar_u32 { uint32_t v; }; -#pragma language=restore -#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) -#endif - -#ifndef __USED - #if __ICCARM_V8 - #define __USED __attribute__((used)) - #else - #define __USED _Pragma("__root") - #endif -#endif - -#ifndef __WEAK - #if __ICCARM_V8 - #define __WEAK __attribute__((weak)) - #else - #define __WEAK _Pragma("__weak") - #endif -#endif - - -#ifndef __ICCARM_INTRINSICS_VERSION__ - #define __ICCARM_INTRINSICS_VERSION__ 0 -#endif - -#if __ICCARM_INTRINSICS_VERSION__ == 2 - - #if defined(__CLZ) - #undef __CLZ - #endif - #if defined(__REVSH) - #undef __REVSH - #endif - #if defined(__RBIT) - #undef __RBIT - #endif - #if defined(__SSAT) - #undef __SSAT - #endif - #if defined(__USAT) - #undef __USAT - #endif - - #include "iccarm_builtin.h" - - #define __disable_fault_irq __iar_builtin_disable_fiq - #define __disable_irq __iar_builtin_disable_interrupt - #define __enable_fault_irq __iar_builtin_enable_fiq - #define __enable_irq __iar_builtin_enable_interrupt - #define __arm_rsr __iar_builtin_rsr - #define __arm_wsr __iar_builtin_wsr - - - #define __get_APSR() (__arm_rsr("APSR")) - #define __get_BASEPRI() (__arm_rsr("BASEPRI")) - #define __get_CONTROL() (__arm_rsr("CONTROL")) - #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) - - #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - #define __get_FPSCR() (__arm_rsr("FPSCR")) - #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) - #else - #define __get_FPSCR() ( 0 ) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #define __get_IPSR() (__arm_rsr("IPSR")) - #define __get_MSP() (__arm_rsr("MSP")) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __get_MSPLIM() (0U) - #else - #define __get_MSPLIM() (__arm_rsr("MSPLIM")) - #endif - #define __get_PRIMASK() (__arm_rsr("PRIMASK")) - #define __get_PSP() (__arm_rsr("PSP")) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __get_PSPLIM() (0U) - #else - #define __get_PSPLIM() (__arm_rsr("PSPLIM")) - #endif - - #define __get_xPSR() (__arm_rsr("xPSR")) - - #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) - #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) - #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) - #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) - #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __set_MSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) - #endif - #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) - #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __set_PSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) - #endif - - #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) - #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) - #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) - #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) - #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) - #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) - #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) - #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) - #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) - #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) - #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) - #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) - #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) - #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __TZ_get_PSPLIM_NS() (0U) - #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) - #else - #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) - #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) - #endif - - #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) - #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) - - #define __NOP __iar_builtin_no_operation - - #define __CLZ __iar_builtin_CLZ - #define __CLREX __iar_builtin_CLREX - - #define __DMB __iar_builtin_DMB - #define __DSB __iar_builtin_DSB - #define __ISB __iar_builtin_ISB - - #define __LDREXB __iar_builtin_LDREXB - #define __LDREXH __iar_builtin_LDREXH - #define __LDREXW __iar_builtin_LDREX - - #define __RBIT __iar_builtin_RBIT - #define __REV __iar_builtin_REV - #define __REV16 __iar_builtin_REV16 - - __IAR_FT int16_t __REVSH(int16_t val) - { - return (int16_t) __iar_builtin_REVSH(val); - } - - #define __ROR __iar_builtin_ROR - #define __RRX __iar_builtin_RRX - - #define __SEV __iar_builtin_SEV - - #if !__IAR_M0_FAMILY - #define __SSAT __iar_builtin_SSAT - #endif - - #define __STREXB __iar_builtin_STREXB - #define __STREXH __iar_builtin_STREXH - #define __STREXW __iar_builtin_STREX - - #if !__IAR_M0_FAMILY - #define __USAT __iar_builtin_USAT - #endif - - #define __WFE __iar_builtin_WFE - #define __WFI __iar_builtin_WFI - - #if __ARM_MEDIA__ - #define __SADD8 __iar_builtin_SADD8 - #define __QADD8 __iar_builtin_QADD8 - #define __SHADD8 __iar_builtin_SHADD8 - #define __UADD8 __iar_builtin_UADD8 - #define __UQADD8 __iar_builtin_UQADD8 - #define __UHADD8 __iar_builtin_UHADD8 - #define __SSUB8 __iar_builtin_SSUB8 - #define __QSUB8 __iar_builtin_QSUB8 - #define __SHSUB8 __iar_builtin_SHSUB8 - #define __USUB8 __iar_builtin_USUB8 - #define __UQSUB8 __iar_builtin_UQSUB8 - #define __UHSUB8 __iar_builtin_UHSUB8 - #define __SADD16 __iar_builtin_SADD16 - #define __QADD16 __iar_builtin_QADD16 - #define __SHADD16 __iar_builtin_SHADD16 - #define __UADD16 __iar_builtin_UADD16 - #define __UQADD16 __iar_builtin_UQADD16 - #define __UHADD16 __iar_builtin_UHADD16 - #define __SSUB16 __iar_builtin_SSUB16 - #define __QSUB16 __iar_builtin_QSUB16 - #define __SHSUB16 __iar_builtin_SHSUB16 - #define __USUB16 __iar_builtin_USUB16 - #define __UQSUB16 __iar_builtin_UQSUB16 - #define __UHSUB16 __iar_builtin_UHSUB16 - #define __SASX __iar_builtin_SASX - #define __QASX __iar_builtin_QASX - #define __SHASX __iar_builtin_SHASX - #define __UASX __iar_builtin_UASX - #define __UQASX __iar_builtin_UQASX - #define __UHASX __iar_builtin_UHASX - #define __SSAX __iar_builtin_SSAX - #define __QSAX __iar_builtin_QSAX - #define __SHSAX __iar_builtin_SHSAX - #define __USAX __iar_builtin_USAX - #define __UQSAX __iar_builtin_UQSAX - #define __UHSAX __iar_builtin_UHSAX - #define __USAD8 __iar_builtin_USAD8 - #define __USADA8 __iar_builtin_USADA8 - #define __SSAT16 __iar_builtin_SSAT16 - #define __USAT16 __iar_builtin_USAT16 - #define __UXTB16 __iar_builtin_UXTB16 - #define __UXTAB16 __iar_builtin_UXTAB16 - #define __SXTB16 __iar_builtin_SXTB16 - #define __SXTAB16 __iar_builtin_SXTAB16 - #define __SMUAD __iar_builtin_SMUAD - #define __SMUADX __iar_builtin_SMUADX - #define __SMMLA __iar_builtin_SMMLA - #define __SMLAD __iar_builtin_SMLAD - #define __SMLADX __iar_builtin_SMLADX - #define __SMLALD __iar_builtin_SMLALD - #define __SMLALDX __iar_builtin_SMLALDX - #define __SMUSD __iar_builtin_SMUSD - #define __SMUSDX __iar_builtin_SMUSDX - #define __SMLSD __iar_builtin_SMLSD - #define __SMLSDX __iar_builtin_SMLSDX - #define __SMLSLD __iar_builtin_SMLSLD - #define __SMLSLDX __iar_builtin_SMLSLDX - #define __SEL __iar_builtin_SEL - #define __QADD __iar_builtin_QADD - #define __QSUB __iar_builtin_QSUB - #define __PKHBT __iar_builtin_PKHBT - #define __PKHTB __iar_builtin_PKHTB - #endif - -#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #define __CLZ __cmsis_iar_clz_not_active - #define __SSAT __cmsis_iar_ssat_not_active - #define __USAT __cmsis_iar_usat_not_active - #define __RBIT __cmsis_iar_rbit_not_active - #define __get_APSR __cmsis_iar_get_APSR_not_active - #endif - - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #define __get_FPSCR __cmsis_iar_get_FPSR_not_active - #define __set_FPSCR __cmsis_iar_set_FPSR_not_active - #endif - - #ifdef __INTRINSICS_INCLUDED - #error intrinsics.h is already included previously! - #endif - - #include - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #undef __CLZ - #undef __SSAT - #undef __USAT - #undef __RBIT - #undef __get_APSR - - __STATIC_INLINE uint8_t __CLZ(uint32_t data) - { - if (data == 0U) { return 32U; } - - uint32_t count = 0U; - uint32_t mask = 0x80000000U; - - while ((data & mask) == 0U) - { - count += 1U; - mask = mask >> 1U; - } - return count; - } - - __STATIC_INLINE uint32_t __RBIT(uint32_t v) - { - uint8_t sc = 31U; - uint32_t r = v; - for (v >>= 1U; v; v >>= 1U) - { - r <<= 1U; - r |= v & 1U; - sc--; - } - return (r << sc); - } - - __STATIC_INLINE uint32_t __get_APSR(void) - { - uint32_t res; - __asm("MRS %0,APSR" : "=r" (res)); - return res; - } - - #endif - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #undef __get_FPSCR - #undef __set_FPSCR - #define __get_FPSCR() (0) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #pragma diag_suppress=Pe940 - #pragma diag_suppress=Pe177 - - #define __enable_irq __enable_interrupt - #define __disable_irq __disable_interrupt - #define __NOP __no_operation - - #define __get_xPSR __get_PSR - - #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) - - __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) - { - return __LDREX((unsigned long *)ptr); - } - - __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) - { - return __STREX(value, (unsigned long *)ptr); - } - #endif - - - /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - #if (__CORTEX_M >= 0x03) - - __IAR_FT uint32_t __RRX(uint32_t value) - { - uint32_t result; - __ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc"); - return(result); - } - - __IAR_FT void __set_BASEPRI_MAX(uint32_t value) - { - __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); - } - - - #define __enable_fault_irq __enable_fiq - #define __disable_fault_irq __disable_fiq - - - #endif /* (__CORTEX_M >= 0x03) */ - - __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) - { - return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); - } - - #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - __IAR_FT uint32_t __get_MSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,MSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_MSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR MSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __get_PSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_PSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) - { - __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PSP_NS(uint32_t value) - { - __asm volatile("MSR PSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_MSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSP_NS(uint32_t value) - { - __asm volatile("MSR MSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_SP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,SP_NS" : "=r" (res)); - return res; - } - __IAR_FT void __TZ_set_SP_NS(uint32_t value) - { - __asm volatile("MSR SP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) - { - __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) - { - __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) - { - __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) - { - __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); - } - - #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - -#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) - -#if __IAR_M0_FAMILY - __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) - { - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; - } - - __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) - { - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; - } -#endif - -#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - - __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) - { - uint32_t res; - __ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) - { - uint32_t res; - __ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) - { - uint32_t res; - __ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return res; - } - - __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) - { - __ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) - { - __ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) - { - __ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); - } - -#endif /* (__CORTEX_M >= 0x03) */ - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - - __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) - { - __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) - { - __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) - { - __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - -#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#undef __IAR_FT -#undef __IAR_M0_FAMILY -#undef __ICCARM_V8 - -#pragma diag_default=Pe940 -#pragma diag_default=Pe177 - -#endif /* __CMSIS_ICCARM_H__ */ +/**************************************************************************//** + * @file cmsis_iccarm.h + * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file + * @version V5.0.7 + * @date 19. June 2018 + ******************************************************************************/ + +//------------------------------------------------------------------------------ +// +// Copyright (c) 2017-2018 IAR Systems +// +// Licensed 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 __CMSIS_ICCARM_H__ +#define __CMSIS_ICCARM_H__ + +#ifndef __ICCARM__ + #error This file should only be compiled by ICCARM +#endif + +#pragma system_include + +#define __IAR_FT _Pragma("inline=forced") __intrinsic + +#if (__VER__ >= 8000000) + #define __ICCARM_V8 1 +#else + #define __ICCARM_V8 0 +#endif + +#ifndef __ALIGNED + #if __ICCARM_V8 + #define __ALIGNED(x) __attribute__((aligned(x))) + #elif (__VER__ >= 7080000) + /* Needs IAR language extensions */ + #define __ALIGNED(x) __attribute__((aligned(x))) + #else + #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. + #define __ALIGNED(x) + #endif +#endif + + +/* Define compiler macros for CPU architecture, used in CMSIS 5. + */ +#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ +/* Macros already defined */ +#else + #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' + #if __ARM_ARCH == 6 + #define __ARM_ARCH_6M__ 1 + #elif __ARM_ARCH == 7 + #if __ARM_FEATURE_DSP + #define __ARM_ARCH_7EM__ 1 + #else + #define __ARM_ARCH_7M__ 1 + #endif + #endif /* __ARM_ARCH */ + #endif /* __ARM_ARCH_PROFILE == 'M' */ +#endif + +/* Alternativ core deduction for older ICCARM's */ +#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ + !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) + #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) + #define __ARM_ARCH_6M__ 1 + #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) + #define __ARM_ARCH_7M__ 1 + #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) + #define __ARM_ARCH_7EM__ 1 + #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #else + #error "Unknown target." + #endif +#endif + + + +#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 + #define __IAR_M0_FAMILY 1 +#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 + #define __IAR_M0_FAMILY 1 +#else + #define __IAR_M0_FAMILY 0 +#endif + + +#ifndef __ASM + #define __ASM __asm +#endif + +#ifndef __INLINE + #define __INLINE inline +#endif + +#ifndef __NO_RETURN + #if __ICCARM_V8 + #define __NO_RETURN __attribute__((__noreturn__)) + #else + #define __NO_RETURN _Pragma("object_attribute=__noreturn") + #endif +#endif + +#ifndef __PACKED + #if __ICCARM_V8 + #define __PACKED __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED __packed + #endif +#endif + +#ifndef __PACKED_STRUCT + #if __ICCARM_V8 + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_STRUCT __packed struct + #endif +#endif + +#ifndef __PACKED_UNION + #if __ICCARM_V8 + #define __PACKED_UNION union __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_UNION __packed union + #endif +#endif + +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif + +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif + +#ifndef __FORCEINLINE + #define __FORCEINLINE _Pragma("inline=forced") +#endif + +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE +#endif + +#ifndef __UNALIGNED_UINT16_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint16_t __iar_uint16_read(void const *ptr) +{ + return *(__packed uint16_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) +#endif + + +#ifndef __UNALIGNED_UINT16_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) +{ + *(__packed uint16_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint32_t __iar_uint32_read(void const *ptr) +{ + return *(__packed uint32_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) +#endif + +#ifndef __UNALIGNED_UINT32_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) +{ + *(__packed uint32_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32 /* deprecated */ +#pragma language=save +#pragma language=extended +__packed struct __iar_u32 { uint32_t v; }; +#pragma language=restore +#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) +#endif + +#ifndef __USED + #if __ICCARM_V8 + #define __USED __attribute__((used)) + #else + #define __USED _Pragma("__root") + #endif +#endif + +#ifndef __WEAK + #if __ICCARM_V8 + #define __WEAK __attribute__((weak)) + #else + #define __WEAK _Pragma("__weak") + #endif +#endif + + +#ifndef __ICCARM_INTRINSICS_VERSION__ + #define __ICCARM_INTRINSICS_VERSION__ 0 +#endif + +#if __ICCARM_INTRINSICS_VERSION__ == 2 + + #if defined(__CLZ) + #undef __CLZ + #endif + #if defined(__REVSH) + #undef __REVSH + #endif + #if defined(__RBIT) + #undef __RBIT + #endif + #if defined(__SSAT) + #undef __SSAT + #endif + #if defined(__USAT) + #undef __USAT + #endif + + #include "iccarm_builtin.h" + + #define __disable_fault_irq __iar_builtin_disable_fiq + #define __disable_irq __iar_builtin_disable_interrupt + #define __enable_fault_irq __iar_builtin_enable_fiq + #define __enable_irq __iar_builtin_enable_interrupt + #define __arm_rsr __iar_builtin_rsr + #define __arm_wsr __iar_builtin_wsr + + + #define __get_APSR() (__arm_rsr("APSR")) + #define __get_BASEPRI() (__arm_rsr("BASEPRI")) + #define __get_CONTROL() (__arm_rsr("CONTROL")) + #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) + + #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + #define __get_FPSCR() (__arm_rsr("FPSCR")) + #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) + #else + #define __get_FPSCR() ( 0 ) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #define __get_IPSR() (__arm_rsr("IPSR")) + #define __get_MSP() (__arm_rsr("MSP")) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __get_MSPLIM() (0U) + #else + #define __get_MSPLIM() (__arm_rsr("MSPLIM")) + #endif + #define __get_PRIMASK() (__arm_rsr("PRIMASK")) + #define __get_PSP() (__arm_rsr("PSP")) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __get_PSPLIM() (0U) + #else + #define __get_PSPLIM() (__arm_rsr("PSPLIM")) + #endif + + #define __get_xPSR() (__arm_rsr("xPSR")) + + #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) + #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) + #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) + #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) + #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __set_MSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) + #endif + #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) + #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __set_PSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) + #endif + + #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) + #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) + #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) + #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) + #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) + #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) + #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) + #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) + #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) + #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) + #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) + #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) + #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) + #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __TZ_get_PSPLIM_NS() (0U) + #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) + #else + #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) + #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) + #endif + + #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) + #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) + + #define __NOP __iar_builtin_no_operation + + #define __CLZ __iar_builtin_CLZ + #define __CLREX __iar_builtin_CLREX + + #define __DMB __iar_builtin_DMB + #define __DSB __iar_builtin_DSB + #define __ISB __iar_builtin_ISB + + #define __LDREXB __iar_builtin_LDREXB + #define __LDREXH __iar_builtin_LDREXH + #define __LDREXW __iar_builtin_LDREX + + #define __RBIT __iar_builtin_RBIT + #define __REV __iar_builtin_REV + #define __REV16 __iar_builtin_REV16 + + __IAR_FT int16_t __REVSH(int16_t val) + { + return (int16_t) __iar_builtin_REVSH(val); + } + + #define __ROR __iar_builtin_ROR + #define __RRX __iar_builtin_RRX + + #define __SEV __iar_builtin_SEV + + #if !__IAR_M0_FAMILY + #define __SSAT __iar_builtin_SSAT + #endif + + #define __STREXB __iar_builtin_STREXB + #define __STREXH __iar_builtin_STREXH + #define __STREXW __iar_builtin_STREX + + #if !__IAR_M0_FAMILY + #define __USAT __iar_builtin_USAT + #endif + + #define __WFE __iar_builtin_WFE + #define __WFI __iar_builtin_WFI + + #if __ARM_MEDIA__ + #define __SADD8 __iar_builtin_SADD8 + #define __QADD8 __iar_builtin_QADD8 + #define __SHADD8 __iar_builtin_SHADD8 + #define __UADD8 __iar_builtin_UADD8 + #define __UQADD8 __iar_builtin_UQADD8 + #define __UHADD8 __iar_builtin_UHADD8 + #define __SSUB8 __iar_builtin_SSUB8 + #define __QSUB8 __iar_builtin_QSUB8 + #define __SHSUB8 __iar_builtin_SHSUB8 + #define __USUB8 __iar_builtin_USUB8 + #define __UQSUB8 __iar_builtin_UQSUB8 + #define __UHSUB8 __iar_builtin_UHSUB8 + #define __SADD16 __iar_builtin_SADD16 + #define __QADD16 __iar_builtin_QADD16 + #define __SHADD16 __iar_builtin_SHADD16 + #define __UADD16 __iar_builtin_UADD16 + #define __UQADD16 __iar_builtin_UQADD16 + #define __UHADD16 __iar_builtin_UHADD16 + #define __SSUB16 __iar_builtin_SSUB16 + #define __QSUB16 __iar_builtin_QSUB16 + #define __SHSUB16 __iar_builtin_SHSUB16 + #define __USUB16 __iar_builtin_USUB16 + #define __UQSUB16 __iar_builtin_UQSUB16 + #define __UHSUB16 __iar_builtin_UHSUB16 + #define __SASX __iar_builtin_SASX + #define __QASX __iar_builtin_QASX + #define __SHASX __iar_builtin_SHASX + #define __UASX __iar_builtin_UASX + #define __UQASX __iar_builtin_UQASX + #define __UHASX __iar_builtin_UHASX + #define __SSAX __iar_builtin_SSAX + #define __QSAX __iar_builtin_QSAX + #define __SHSAX __iar_builtin_SHSAX + #define __USAX __iar_builtin_USAX + #define __UQSAX __iar_builtin_UQSAX + #define __UHSAX __iar_builtin_UHSAX + #define __USAD8 __iar_builtin_USAD8 + #define __USADA8 __iar_builtin_USADA8 + #define __SSAT16 __iar_builtin_SSAT16 + #define __USAT16 __iar_builtin_USAT16 + #define __UXTB16 __iar_builtin_UXTB16 + #define __UXTAB16 __iar_builtin_UXTAB16 + #define __SXTB16 __iar_builtin_SXTB16 + #define __SXTAB16 __iar_builtin_SXTAB16 + #define __SMUAD __iar_builtin_SMUAD + #define __SMUADX __iar_builtin_SMUADX + #define __SMMLA __iar_builtin_SMMLA + #define __SMLAD __iar_builtin_SMLAD + #define __SMLADX __iar_builtin_SMLADX + #define __SMLALD __iar_builtin_SMLALD + #define __SMLALDX __iar_builtin_SMLALDX + #define __SMUSD __iar_builtin_SMUSD + #define __SMUSDX __iar_builtin_SMUSDX + #define __SMLSD __iar_builtin_SMLSD + #define __SMLSDX __iar_builtin_SMLSDX + #define __SMLSLD __iar_builtin_SMLSLD + #define __SMLSLDX __iar_builtin_SMLSLDX + #define __SEL __iar_builtin_SEL + #define __QADD __iar_builtin_QADD + #define __QSUB __iar_builtin_QSUB + #define __PKHBT __iar_builtin_PKHBT + #define __PKHTB __iar_builtin_PKHTB + #endif + +#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #define __CLZ __cmsis_iar_clz_not_active + #define __SSAT __cmsis_iar_ssat_not_active + #define __USAT __cmsis_iar_usat_not_active + #define __RBIT __cmsis_iar_rbit_not_active + #define __get_APSR __cmsis_iar_get_APSR_not_active + #endif + + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #define __get_FPSCR __cmsis_iar_get_FPSR_not_active + #define __set_FPSCR __cmsis_iar_set_FPSR_not_active + #endif + + #ifdef __INTRINSICS_INCLUDED + #error intrinsics.h is already included previously! + #endif + + #include + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #undef __CLZ + #undef __SSAT + #undef __USAT + #undef __RBIT + #undef __get_APSR + + __STATIC_INLINE uint8_t __CLZ(uint32_t data) + { + if (data == 0U) { return 32U; } + + uint32_t count = 0U; + uint32_t mask = 0x80000000U; + + while ((data & mask) == 0U) + { + count += 1U; + mask = mask >> 1U; + } + return count; + } + + __STATIC_INLINE uint32_t __RBIT(uint32_t v) + { + uint8_t sc = 31U; + uint32_t r = v; + for (v >>= 1U; v; v >>= 1U) + { + r <<= 1U; + r |= v & 1U; + sc--; + } + return (r << sc); + } + + __STATIC_INLINE uint32_t __get_APSR(void) + { + uint32_t res; + __asm("MRS %0,APSR" : "=r" (res)); + return res; + } + + #endif + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #undef __get_FPSCR + #undef __set_FPSCR + #define __get_FPSCR() (0) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #pragma diag_suppress=Pe940 + #pragma diag_suppress=Pe177 + + #define __enable_irq __enable_interrupt + #define __disable_irq __disable_interrupt + #define __NOP __no_operation + + #define __get_xPSR __get_PSR + + #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) + + __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) + { + return __LDREX((unsigned long *)ptr); + } + + __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) + { + return __STREX(value, (unsigned long *)ptr); + } + #endif + + + /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + #if (__CORTEX_M >= 0x03) + + __IAR_FT uint32_t __RRX(uint32_t value) + { + uint32_t result; + __ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc"); + return(result); + } + + __IAR_FT void __set_BASEPRI_MAX(uint32_t value) + { + __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); + } + + + #define __enable_fault_irq __enable_fiq + #define __disable_fault_irq __disable_fiq + + + #endif /* (__CORTEX_M >= 0x03) */ + + __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) + { + return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); + } + + #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + __IAR_FT uint32_t __get_MSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,MSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_MSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR MSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __get_PSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_PSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) + { + __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PSP_NS(uint32_t value) + { + __asm volatile("MSR PSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_MSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSP_NS(uint32_t value) + { + __asm volatile("MSR MSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_SP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,SP_NS" : "=r" (res)); + return res; + } + __IAR_FT void __TZ_set_SP_NS(uint32_t value) + { + __asm volatile("MSR SP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) + { + __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) + { + __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) + { + __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) + { + __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); + } + + #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + +#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) + +#if __IAR_M0_FAMILY + __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) + { + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; + } + + __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) + { + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; + } +#endif + +#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + + __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) + { + uint32_t res; + __ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) + { + uint32_t res; + __ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) + { + uint32_t res; + __ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return res; + } + + __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) + { + __ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) + { + __ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) + { + __ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); + } + +#endif /* (__CORTEX_M >= 0x03) */ + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + + __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) + { + __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) + { + __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) + { + __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + +#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#undef __IAR_FT +#undef __IAR_M0_FAMILY +#undef __ICCARM_V8 + +#pragma diag_default=Pe940 +#pragma diag_default=Pe177 + +#endif /* __CMSIS_ICCARM_H__ */ diff --git a/Drivers/CMSIS/Include/cmsis_version.h b/Drivers/CMSIS/Include/cmsis_version.h index 660f612..ae3f2e3 100644 --- a/Drivers/CMSIS/Include/cmsis_version.h +++ b/Drivers/CMSIS/Include/cmsis_version.h @@ -1,39 +1,39 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.2 - * @date 19. April 2017 - ******************************************************************************/ -/* - * Copyright (c) 2009-2017 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif +/**************************************************************************//** + * @file cmsis_version.h + * @brief CMSIS Core(M) Version definitions + * @version V5.0.2 + * @date 19. April 2017 + ******************************************************************************/ +/* + * Copyright (c) 2009-2017 ARM Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CMSIS_VERSION_H +#define __CMSIS_VERSION_H + +/* CMSIS Version definitions */ +#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ +#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ +#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ + __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ +#endif diff --git a/Drivers/CMSIS/Include/core_armv8mbl.h b/Drivers/CMSIS/Include/core_armv8mbl.h index 251e4ed..ec76ab2 100644 --- a/Drivers/CMSIS/Include/core_armv8mbl.h +++ b/Drivers/CMSIS/Include/core_armv8mbl.h @@ -1,1918 +1,1918 @@ -/**************************************************************************//** - * @file core_armv8mbl.h - * @brief CMSIS Armv8-M Baseline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 22. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MBL_H_GENERIC -#define __CORE_ARMV8MBL_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MBL - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS definitions */ -#define __ARMv8MBL_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MBL_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MBL_CMSIS_VERSION ((__ARMv8MBL_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MBL_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M ( 2U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MBL_H_DEPENDANT -#define __CORE_ARMV8MBL_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MBL_REV - #define __ARMv8MBL_REV 0x0000U - #warning "__ARMv8MBL_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif - - #ifndef __ETM_PRESENT - #define __ETM_PRESENT 0U - #warning "__ETM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MTB_PRESENT - #define __MTB_PRESENT 0U - #warning "__MTB_PRESENT not defined in device header file; using default!" - #endif - -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MBL */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - uint32_t RESERVED0[6U]; - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - uint32_t RESERVED0[7U]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#endif -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register */ -#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ -#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_armv8mbl.h + * @brief CMSIS Armv8-M Baseline Core Peripheral Access Layer Header File + * @version V5.0.7 + * @date 22. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_ARMV8MBL_H_GENERIC +#define __CORE_ARMV8MBL_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_ARMv8MBL + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS definitions */ +#define __ARMv8MBL_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __ARMv8MBL_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __ARMv8MBL_CMSIS_VERSION ((__ARMv8MBL_CMSIS_VERSION_MAIN << 16U) | \ + __ARMv8MBL_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M ( 2U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_ARMV8MBL_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_ARMV8MBL_H_DEPENDANT +#define __CORE_ARMV8MBL_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __ARMv8MBL_REV + #define __ARMv8MBL_REV 0x0000U + #warning "__ARMv8MBL_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __SAUREGION_PRESENT + #define __SAUREGION_PRESENT 0U + #warning "__SAUREGION_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __VTOR_PRESENT + #define __VTOR_PRESENT 0U + #warning "__VTOR_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif + + #ifndef __ETM_PRESENT + #define __ETM_PRESENT 0U + #warning "__ETM_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MTB_PRESENT + #define __MTB_PRESENT 0U + #warning "__MTB_PRESENT not defined in device header file; using default!" + #endif + +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group ARMv8MBL */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core SAU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[16U]; + __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[16U]; + __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[16U]; + __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[16U]; + __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[16U]; + __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ + uint32_t RESERVED5[16U]; + __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ +#else + uint32_t RESERVED0; +#endif + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ +#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ + +#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ +#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ + +#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ +#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ +#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ +#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ + +#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ +#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ + +#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ +#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ +#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ + +#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ +#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ +#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ +#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ + +#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ +#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + uint32_t RESERVED0[6U]; + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + uint32_t RESERVED3[1U]; + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED4[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + uint32_t RESERVED5[1U]; + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED6[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + uint32_t RESERVED7[1U]; + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ + uint32_t RESERVED8[1U]; + __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ + uint32_t RESERVED9[1U]; + __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ + uint32_t RESERVED10[1U]; + __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ + uint32_t RESERVED11[1U]; + __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ + uint32_t RESERVED12[1U]; + __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ + uint32_t RESERVED13[1U]; + __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ + uint32_t RESERVED14[1U]; + __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ + uint32_t RESERVED15[1U]; + __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ + uint32_t RESERVED16[1U]; + __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ + uint32_t RESERVED17[1U]; + __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ + uint32_t RESERVED18[1U]; + __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ + uint32_t RESERVED19[1U]; + __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ + uint32_t RESERVED20[1U]; + __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ + uint32_t RESERVED21[1U]; + __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ + uint32_t RESERVED22[1U]; + __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ + uint32_t RESERVED23[1U]; + __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ + uint32_t RESERVED24[1U]; + __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ + uint32_t RESERVED25[1U]; + __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ + uint32_t RESERVED26[1U]; + __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ + uint32_t RESERVED27[1U]; + __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ + uint32_t RESERVED28[1U]; + __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ + uint32_t RESERVED29[1U]; + __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ + uint32_t RESERVED30[1U]; + __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ + uint32_t RESERVED31[1U]; + __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ +#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ + +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ +#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ + +#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ +#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ + uint32_t RESERVED3[809U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ + uint32_t RESERVED4[4U]; + __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ +#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ +#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI Periodic Synchronization Control Register Definitions */ +#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ +#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ + +/* TPI Software Lock Status Register Definitions */ +#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ +#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ + +#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ +#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ + +#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ +#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ +#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ + uint32_t RESERVED0[7U]; + union { + __IOM uint32_t MAIR[2]; + struct { + __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ + __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ + }; + }; +} MPU_Type; + +#define MPU_TYPE_RALIASES 1U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ +#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ + +#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ +#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ + +#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ +#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ + +#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ +#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ + +/* MPU Region Limit Address Register Definitions */ +#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ +#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ + +#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ +#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ + +#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ +#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ + +/* MPU Memory Attribute Indirection Register 0 Definitions */ +#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ +#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ + +#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ +#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ + +#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ +#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ + +#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ +#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ + +/* MPU Memory Attribute Indirection Register 1 Definitions */ +#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ +#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ + +#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ +#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ + +#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ +#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ + +#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ +#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SAU Security Attribution Unit (SAU) + \brief Type definitions for the Security Attribution Unit (SAU) + @{ + */ + +/** + \brief Structure type to access the Security Attribution Unit (SAU). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ + __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ +#endif +} SAU_Type; + +/* SAU Control Register Definitions */ +#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ +#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ + +#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ +#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ + +/* SAU Type Register Definitions */ +#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ +#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ + +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) +/* SAU Region Number Register Definitions */ +#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ +#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ + +/* SAU Region Base Address Register Definitions */ +#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ +#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ + +/* SAU Region Limit Address Register Definitions */ +#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ +#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ + +#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ +#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ + +#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ +#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ + +#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ + +/*@} end of group CMSIS_SAU */ +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ + uint32_t RESERVED4[1U]; + __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ + __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ +#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ +#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/* Debug Authentication Control Register Definitions */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ + +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ + +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ + +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ + +/* Debug Security Control and Status Register Definitions */ +#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ +#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ + +#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ +#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ + +#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ +#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ + #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ + #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ + #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ + #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ + #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ + #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ + #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + + + #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ + #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ + #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ + #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ + #endif + + #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ + #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ + #endif + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ + #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ + #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ + #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ + #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ + + #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ + #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ + #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ + #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ + #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ + #endif + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* Special LR values for Secure/Non-Secure call handling and exception handling */ + +/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ +#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ + +/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ +#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ +#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ +#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ +#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ +#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ +#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ +#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ + +/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ +#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ +#else +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ +#endif + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + +#define __NVIC_SetPriorityGrouping(X) (void)(X) +#define __NVIC_GetPriorityGrouping() (0U) + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Get Interrupt Target State + \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + \return 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Target State + \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Clear Interrupt Target State + \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + If VTOR is not present address 0 must be mapped to SRAM. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Enable Interrupt (non-secure) + \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status (non-secure) + \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt (non-secure) + \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Pending Interrupt (non-secure) + \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt (non-secure) + \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt (non-secure) + \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt (non-secure) + \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority (non-secure) + \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every non-secure processor exception. + */ +__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority (non-secure) + \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv8.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ########################## SAU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SAUFunctions SAU Functions + \brief Functions that configure the SAU. + @{ + */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + +/** + \brief Enable SAU + \details Enables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Enable(void) +{ + SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); +} + + + +/** + \brief Disable SAU + \details Disables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Disable(void) +{ + SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); +} + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_SAUFunctions */ + + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief System Tick Configuration (non-secure) + \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_ARMV8MBL_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_armv8mml.h b/Drivers/CMSIS/Include/core_armv8mml.h index 3a3148e..2d0f106 100644 --- a/Drivers/CMSIS/Include/core_armv8mml.h +++ b/Drivers/CMSIS/Include/core_armv8mml.h @@ -1,2927 +1,2927 @@ -/**************************************************************************//** - * @file core_armv8mml.h - * @brief CMSIS Armv8-M Mainline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 06. July 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MML_H_GENERIC -#define __CORE_ARMV8MML_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MML - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS Armv8MML definitions */ -#define __ARMv8MML_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MML_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MML_CMSIS_VERSION ((__ARMv8MML_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MML_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (81U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MML_H_DEPENDANT -#define __CORE_ARMV8MML_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MML_REV - #define __ARMv8MML_REV 0x0000U - #warning "__ARMv8MML_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DSP_PRESENT - #define __DSP_PRESENT 0U - #warning "__DSP_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MML */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ -#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ - uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ - uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ -#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ - -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED6[580U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ - uint32_t RESERVED3[92U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ -#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ -#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ - -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ -#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ -#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Non-Secure Access Control Register Definitions */ -#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ -#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ - -#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ -#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ - -#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ -#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ - __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ - uint32_t RESERVED6[4U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Stimulus Port Register Definitions */ -#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ -#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ - -#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ -#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ -#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ - -#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ -#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ - uint32_t RESERVED32[934U]; - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ - uint32_t RESERVED33[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ -#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ - __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ - __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ - __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ - uint32_t RESERVED0[1]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#else - uint32_t RESERVED0[3]; -#endif - __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ - __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/* Secure Fault Status Register Definitions */ -#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ -#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ - -#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ -#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ - -#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ -#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ - -#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ -#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ - -#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ -#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ - -#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ -#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ - -#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ -#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ - -#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ -#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ -#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ - -#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ -#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ - -#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ -#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ - -#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ -#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ - -#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ -#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ - -#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ -#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ -#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ -#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - - #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ - #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - - #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ - #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Grouping (non-secure) - \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB_NS->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB_NS->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping (non-secure) - \details Reads the priority grouping field from the non-secure NVIC when in secure state. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) -{ - return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_armv8mml.h + * @brief CMSIS Armv8-M Mainline Core Peripheral Access Layer Header File + * @version V5.0.7 + * @date 06. July 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_ARMV8MML_H_GENERIC +#define __CORE_ARMV8MML_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_ARMv8MML + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS Armv8MML definitions */ +#define __ARMv8MML_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __ARMv8MML_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __ARMv8MML_CMSIS_VERSION ((__ARMv8MML_CMSIS_VERSION_MAIN << 16U) | \ + __ARMv8MML_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (81U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined(__ARM_FEATURE_DSP) + #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined(__ARM_FEATURE_DSP) + #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined(__ARM_FEATURE_DSP) + #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined(__ARM_FEATURE_DSP) + #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_ARMV8MML_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_ARMV8MML_H_DEPENDANT +#define __CORE_ARMV8MML_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __ARMv8MML_REV + #define __ARMv8MML_REV 0x0000U + #warning "__ARMv8MML_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __SAUREGION_PRESENT + #define __SAUREGION_PRESENT 0U + #warning "__SAUREGION_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DSP_PRESENT + #define __DSP_PRESENT 0U + #warning "__DSP_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group ARMv8MML */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core SAU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ + uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ + uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ + uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ +#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ + +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[16U]; + __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[16U]; + __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[16U]; + __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[16U]; + __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[16U]; + __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ + uint32_t RESERVED5[16U]; + __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED6[580U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ + __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ + __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ + __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ + uint32_t RESERVED3[92U]; + __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ + uint32_t RESERVED4[15U]; + __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ + uint32_t RESERVED5[1U]; + __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ + uint32_t RESERVED6[1U]; + __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ + __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ + __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ + __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ + __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ + __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ + __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ + __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ + uint32_t RESERVED7[6U]; + __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ + __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ + __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ + __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ + __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ + uint32_t RESERVED8[1U]; + __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ +#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ + +#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ +#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ + +#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ +#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ +#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ +#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ + +#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ +#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ +#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ +#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ + +#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ +#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ +#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ + +#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ +#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ + +#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ +#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ + +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ +#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ + +#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ +#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ +#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ +#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/* SCB Non-Secure Access Control Register Definitions */ +#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ +#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ + +#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ +#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ + +#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ +#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ + +/* SCB Cache Level ID Register Definitions */ +#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ +#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ + +#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ +#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ + +/* SCB Cache Type Register Definitions */ +#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ +#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ + +#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ +#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ + +#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ +#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ + +#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ +#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ + +#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ +#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ + +/* SCB Cache Size ID Register Definitions */ +#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ +#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ + +#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ +#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ + +#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ +#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ + +#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ +#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ + +#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ +#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ + +#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ +#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ + +#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ +#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ + +/* SCB Cache Size Selection Register Definitions */ +#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ +#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ + +#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ +#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ + +/* SCB Software Triggered Interrupt Register Definitions */ +#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ +#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ + +/* SCB D-Cache Invalidate by Set-way Register Definitions */ +#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ +#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ + +#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ +#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ + +/* SCB D-Cache Clean by Set-way Register Definitions */ +#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ +#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ + +#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ +#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ + +/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ +#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ +#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ + +#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ +#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ + +/* Instruction Tightly-Coupled Memory Control Register Definitions */ +#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ +#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ + +#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ +#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ + +#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ +#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ + +#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ +#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ + +/* Data Tightly-Coupled Memory Control Register Definitions */ +#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ +#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ + +#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ +#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ + +#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ +#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ + +#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ +#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ + +/* AHBP Control Register Definitions */ +#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ +#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ + +#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ +#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ + +/* L1 Cache Control Register Definitions */ +#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ +#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ + +#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ +#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ + +#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ +#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ + +/* AHBS Control Register Definitions */ +#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ +#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ + +#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ +#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ + +#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ +#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ + +/* Auxiliary Bus Fault Status Register Definitions */ +#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ +#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ + +#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ +#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ + +#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ +#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ + +#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ +#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ + +#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ +#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ + +#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ +#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ + __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[1U]; + __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ + uint32_t RESERVED6[4U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Stimulus Port Register Definitions */ +#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ +#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ + +#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ +#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ +#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ + +#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ +#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + uint32_t RESERVED3[1U]; + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED4[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + uint32_t RESERVED5[1U]; + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED6[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + uint32_t RESERVED7[1U]; + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ + uint32_t RESERVED8[1U]; + __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ + uint32_t RESERVED9[1U]; + __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ + uint32_t RESERVED10[1U]; + __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ + uint32_t RESERVED11[1U]; + __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ + uint32_t RESERVED12[1U]; + __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ + uint32_t RESERVED13[1U]; + __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ + uint32_t RESERVED14[1U]; + __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ + uint32_t RESERVED15[1U]; + __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ + uint32_t RESERVED16[1U]; + __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ + uint32_t RESERVED17[1U]; + __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ + uint32_t RESERVED18[1U]; + __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ + uint32_t RESERVED19[1U]; + __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ + uint32_t RESERVED20[1U]; + __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ + uint32_t RESERVED21[1U]; + __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ + uint32_t RESERVED22[1U]; + __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ + uint32_t RESERVED23[1U]; + __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ + uint32_t RESERVED24[1U]; + __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ + uint32_t RESERVED25[1U]; + __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ + uint32_t RESERVED26[1U]; + __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ + uint32_t RESERVED27[1U]; + __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ + uint32_t RESERVED28[1U]; + __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ + uint32_t RESERVED29[1U]; + __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ + uint32_t RESERVED30[1U]; + __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ + uint32_t RESERVED31[1U]; + __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ + uint32_t RESERVED32[934U]; + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ + uint32_t RESERVED33[1U]; + __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ +#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ +#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ + +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ +#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ + +#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ +#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ + uint32_t RESERVED3[809U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ + uint32_t RESERVED4[4U]; + __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ +#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ +#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI Periodic Synchronization Control Register Definitions */ +#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ +#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ + +/* TPI Software Lock Status Register Definitions */ +#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ +#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ + +#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ +#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ + +#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ +#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ +#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ + __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ + __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ + __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ + uint32_t RESERVED0[1]; + union { + __IOM uint32_t MAIR[2]; + struct { + __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ + __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ + }; + }; +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ +#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ + +#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ +#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ + +#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ +#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ + +#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ +#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ + +/* MPU Region Limit Address Register Definitions */ +#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ +#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ + +#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ +#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ + +#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ +#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ + +/* MPU Memory Attribute Indirection Register 0 Definitions */ +#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ +#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ + +#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ +#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ + +#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ +#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ + +#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ +#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ + +/* MPU Memory Attribute Indirection Register 1 Definitions */ +#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ +#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ + +#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ +#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ + +#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ +#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ + +#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ +#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SAU Security Attribution Unit (SAU) + \brief Type definitions for the Security Attribution Unit (SAU) + @{ + */ + +/** + \brief Structure type to access the Security Attribution Unit (SAU). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ + __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ +#else + uint32_t RESERVED0[3]; +#endif + __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ + __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ +} SAU_Type; + +/* SAU Control Register Definitions */ +#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ +#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ + +#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ +#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ + +/* SAU Type Register Definitions */ +#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ +#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ + +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) +/* SAU Region Number Register Definitions */ +#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ +#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ + +/* SAU Region Base Address Register Definitions */ +#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ +#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ + +/* SAU Region Limit Address Register Definitions */ +#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ +#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ + +#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ +#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ + +#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ +#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ + +#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ + +/* Secure Fault Status Register Definitions */ +#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ +#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ + +#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ +#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ + +#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ +#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ + +#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ +#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ + +#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ +#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ + +#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ +#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ + +#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ +#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ + +#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ +#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ + +/*@} end of group CMSIS_SAU */ +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ +#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ + +#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ +#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ + +#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ +#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ + +#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ +#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ + +#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ +#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ + +#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ +#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ +#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ +#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ + uint32_t RESERVED4[1U]; + __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ + __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ +#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/* Debug Authentication Control Register Definitions */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ + +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ + +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ + +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ + +/* Debug Security Control and Status Register Definitions */ +#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ +#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ + +#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ +#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ + +#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ +#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ + #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ + #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ + #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ + #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ + #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ + #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ + #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ + #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + + #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ + #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ + #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ + #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ + #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ + #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ + #endif + + #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ + #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ + #endif + + #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ + #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ + #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ + #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ + #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ + #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ + + #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ + #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ + #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ + #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ + #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ + #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ + #endif + + #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ + #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* Special LR values for Secure/Non-Secure call handling and exception handling */ + +/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ +#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ + +/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ +#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ +#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ +#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ +#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ +#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ +#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ +#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ + +/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ +#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ +#else +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ +#endif + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Get Interrupt Target State + \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + \return 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Target State + \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Clear Interrupt Target State + \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Set Priority Grouping (non-secure) + \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB_NS->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ + SCB_NS->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping (non-secure) + \details Reads the priority grouping field from the non-secure NVIC when in secure state. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) +{ + return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt (non-secure) + \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status (non-secure) + \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt (non-secure) + \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Pending Interrupt (non-secure) + \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt (non-secure) + \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt (non-secure) + \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt (non-secure) + \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority (non-secure) + \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every non-secure processor exception. + */ +__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority (non-secure) + \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv8.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = FPU->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) + { + return 2U; /* Double + Single precision FPU */ + } + else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ########################## SAU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SAUFunctions SAU Functions + \brief Functions that configure the SAU. + @{ + */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + +/** + \brief Enable SAU + \details Enables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Enable(void) +{ + SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); +} + + + +/** + \brief Disable SAU + \details Disables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Disable(void) +{ + SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); +} + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_SAUFunctions */ + + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief System Tick Configuration (non-secure) + \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_ARMV8MML_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm0.h b/Drivers/CMSIS/Include/core_cm0.h index f929bba..6f82227 100644 --- a/Drivers/CMSIS/Include/core_cm0.h +++ b/Drivers/CMSIS/Include/core_cm0.h @@ -1,949 +1,949 @@ -/**************************************************************************//** - * @file core_cm0.h - * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File - * @version V5.0.5 - * @date 28. May 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM0_H_GENERIC -#define __CORE_CM0_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M0 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM0 definitions */ -#define __CM0_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM0_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16U) | \ - __CM0_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (0U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM0_H_DEPENDANT -#define __CORE_CM0_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM0_REV - #define __CM0_REV 0x0000U - #warning "__CM0_REV not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M0 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t _reserved0:1; /*!< bit: 0 Reserved */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - uint32_t RESERVED0; - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the Cortex-M0 header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0 */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - Address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)0x0U; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)0x0U; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm0.h + * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File + * @version V5.0.5 + * @date 28. May 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM0_H_GENERIC +#define __CORE_CM0_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M0 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM0 definitions */ +#define __CM0_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM0_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16U) | \ + __CM0_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (0U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM0_H_DEPENDANT +#define __CORE_CM0_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM0_REV + #define __CM0_REV 0x0000U + #warning "__CM0_REV not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M0 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t _reserved0:1; /*!< bit: 0 Reserved */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31U]; + __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31U]; + __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31U]; + __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31U]; + uint32_t RESERVED4[64U]; + __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + uint32_t RESERVED0; + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. + Therefore they are not covered by the Cortex-M0 header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ +/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0 */ + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + +#define __NVIC_SetPriorityGrouping(X) (void)(X) +#define __NVIC_GetPriorityGrouping() (0U) + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + Address 0 must be mapped to SRAM. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)0x0U; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)0x0U; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm0plus.h b/Drivers/CMSIS/Include/core_cm0plus.h index 424011a..b9377e8 100644 --- a/Drivers/CMSIS/Include/core_cm0plus.h +++ b/Drivers/CMSIS/Include/core_cm0plus.h @@ -1,1083 +1,1083 @@ -/**************************************************************************//** - * @file core_cm0plus.h - * @brief CMSIS Cortex-M0+ Core Peripheral Access Layer Header File - * @version V5.0.6 - * @date 28. May 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM0PLUS_H_GENERIC -#define __CORE_CM0PLUS_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex-M0+ - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM0+ definitions */ -#define __CM0PLUS_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM0PLUS_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM0PLUS_CMSIS_VERSION ((__CM0PLUS_CMSIS_VERSION_MAIN << 16U) | \ - __CM0PLUS_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (0U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM0PLUS_H_DEPENDANT -#define __CORE_CM0PLUS_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM0PLUS_REV - #define __CM0PLUS_REV 0x0000U - #warning "__CM0PLUS_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex-M0+ */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Interrupt Control State Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 8U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0xFFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Cortex-M0+ Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the Cortex-M0+ header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0+ */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; - -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm0plus.h + * @brief CMSIS Cortex-M0+ Core Peripheral Access Layer Header File + * @version V5.0.6 + * @date 28. May 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM0PLUS_H_GENERIC +#define __CORE_CM0PLUS_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex-M0+ + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM0+ definitions */ +#define __CM0PLUS_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM0PLUS_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM0PLUS_CMSIS_VERSION ((__CM0PLUS_CMSIS_VERSION_MAIN << 16U) | \ + __CM0PLUS_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (0U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0PLUS_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM0PLUS_H_DEPENDANT +#define __CORE_CM0PLUS_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM0PLUS_REV + #define __CM0PLUS_REV 0x0000U + #warning "__CM0PLUS_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __VTOR_PRESENT + #define __VTOR_PRESENT 0U + #warning "__VTOR_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex-M0+ */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core MPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31U]; + __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31U]; + __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31U]; + __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31U]; + uint32_t RESERVED4[64U]; + __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ +#else + uint32_t RESERVED0; +#endif + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) +/* SCB Interrupt Control State Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 8U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0xFFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 1U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Cortex-M0+ Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. + Therefore they are not covered by the Cortex-M0+ header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ +/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0+ */ + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + +#define __NVIC_SetPriorityGrouping(X) (void)(X) +#define __NVIC_GetPriorityGrouping() (0U) + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + If VTOR is not present address 0 must be mapped to SRAM. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; + +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM0PLUS_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm1.h b/Drivers/CMSIS/Include/core_cm1.h index 0ed678e..fd1c407 100644 --- a/Drivers/CMSIS/Include/core_cm1.h +++ b/Drivers/CMSIS/Include/core_cm1.h @@ -1,976 +1,976 @@ -/**************************************************************************//** - * @file core_cm1.h - * @brief CMSIS Cortex-M1 Core Peripheral Access Layer Header File - * @version V1.0.0 - * @date 23. July 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM1_H_GENERIC -#define __CORE_CM1_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M1 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM1 definitions */ -#define __CM1_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM1_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM1_CMSIS_VERSION ((__CM1_CMSIS_VERSION_MAIN << 16U) | \ - __CM1_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (1U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM1_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM1_H_DEPENDANT -#define __CORE_CM1_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM1_REV - #define __CM1_REV 0x0100U - #warning "__CM1_REV not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M1 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t _reserved0:1; /*!< bit: 0 Reserved */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - uint32_t RESERVED0; - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_ITCMUAEN_Pos 4U /*!< ACTLR: Instruction TCM Upper Alias Enable Position */ -#define SCnSCB_ACTLR_ITCMUAEN_Msk (1UL << SCnSCB_ACTLR_ITCMUAEN_Pos) /*!< ACTLR: Instruction TCM Upper Alias Enable Mask */ - -#define SCnSCB_ACTLR_ITCMLAEN_Pos 3U /*!< ACTLR: Instruction TCM Lower Alias Enable Position */ -#define SCnSCB_ACTLR_ITCMLAEN_Msk (1UL << SCnSCB_ACTLR_ITCMLAEN_Pos) /*!< ACTLR: Instruction TCM Lower Alias Enable Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Cortex-M1 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the Cortex-M1 header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M1 */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - Address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)0x0U; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)0x0U; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM1_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm1.h + * @brief CMSIS Cortex-M1 Core Peripheral Access Layer Header File + * @version V1.0.0 + * @date 23. July 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM1_H_GENERIC +#define __CORE_CM1_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M1 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM1 definitions */ +#define __CM1_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM1_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM1_CMSIS_VERSION ((__CM1_CMSIS_VERSION_MAIN << 16U) | \ + __CM1_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (1U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM1_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM1_H_DEPENDANT +#define __CORE_CM1_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM1_REV + #define __CM1_REV 0x0100U + #warning "__CM1_REV not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M1 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t _reserved0:1; /*!< bit: 0 Reserved */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31U]; + __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31U]; + __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31U]; + __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31U]; + uint32_t RESERVED4[64U]; + __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + uint32_t RESERVED0; + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_ITCMUAEN_Pos 4U /*!< ACTLR: Instruction TCM Upper Alias Enable Position */ +#define SCnSCB_ACTLR_ITCMUAEN_Msk (1UL << SCnSCB_ACTLR_ITCMUAEN_Pos) /*!< ACTLR: Instruction TCM Upper Alias Enable Mask */ + +#define SCnSCB_ACTLR_ITCMLAEN_Pos 3U /*!< ACTLR: Instruction TCM Lower Alias Enable Position */ +#define SCnSCB_ACTLR_ITCMLAEN_Msk (1UL << SCnSCB_ACTLR_ITCMLAEN_Pos) /*!< ACTLR: Instruction TCM Lower Alias Enable Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Cortex-M1 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. + Therefore they are not covered by the Cortex-M1 header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ +/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M1 */ + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + +#define __NVIC_SetPriorityGrouping(X) (void)(X) +#define __NVIC_GetPriorityGrouping() (0U) + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + Address 0 must be mapped to SRAM. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)0x0U; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)0x0U; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM1_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm23.h b/Drivers/CMSIS/Include/core_cm23.h index acbc5df..8202a8d 100644 --- a/Drivers/CMSIS/Include/core_cm23.h +++ b/Drivers/CMSIS/Include/core_cm23.h @@ -1,1993 +1,1993 @@ -/**************************************************************************//** - * @file core_cm23.h - * @brief CMSIS Cortex-M23 Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 22. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM23_H_GENERIC -#define __CORE_CM23_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M23 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS definitions */ -#define __CM23_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM23_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM23_CMSIS_VERSION ((__CM23_CMSIS_VERSION_MAIN << 16U) | \ - __CM23_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (23U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM23_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM23_H_DEPENDANT -#define __CORE_CM23_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM23_REV - #define __CM23_REV 0x0000U - #warning "__CM23_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif - - #ifndef __ETM_PRESENT - #define __ETM_PRESENT 0U - #warning "__ETM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MTB_PRESENT - #define __MTB_PRESENT 0U - #warning "__MTB_PRESENT not defined in device header file; using default!" - #endif - -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M23 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - uint32_t RESERVED0[6U]; - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t ITFTTD0; /*!< Offset: 0xEEC (R/ ) Integration Test FIFO Test Data 0 Register */ - __IOM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/W) Integration Test ATB Control Register 2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) Integration Test ATB Control Register 0 */ - __IM uint32_t ITFTTD1; /*!< Offset: 0xEFC (R/ ) Integration Test FIFO Test Data 1 Register */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) Device Configuration Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Identifier Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration Test FIFO Test Data 0 Register Definitions */ -#define TPI_ITFTTD0_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD0: ATB Interface 2 ATVALIDPosition */ -#define TPI_ITFTTD0_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 2 ATVALID Mask */ - -#define TPI_ITFTTD0_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD0: ATB Interface 2 byte count Position */ -#define TPI_ITFTTD0_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 2 byte count Mask */ - -#define TPI_ITFTTD0_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Position */ -#define TPI_ITFTTD0_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Mask */ - -#define TPI_ITFTTD0_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD0: ATB Interface 1 byte count Position */ -#define TPI_ITFTTD0_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 1 byte countt Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data2_Pos 16U /*!< TPI ITFTTD0: ATB Interface 1 data2 Position */ -#define TPI_ITFTTD0_ATB_IF1_data2_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data2 Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data1_Pos 8U /*!< TPI ITFTTD0: ATB Interface 1 data1 Position */ -#define TPI_ITFTTD0_ATB_IF1_data1_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data1 Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data0_Pos 0U /*!< TPI ITFTTD0: ATB Interface 1 data0 Position */ -#define TPI_ITFTTD0_ATB_IF1_data0_Msk (0xFFUL /*<< TPI_ITFTTD0_ATB_IF1_data0_Pos*/) /*!< TPI ITFTTD0: ATB Interface 1 data0 Mask */ - -/* TPI Integration Test ATB Control Register 2 Register Definitions */ -#define TPI_ITATBCTR2_AFVALID2S_Pos 1U /*!< TPI ITATBCTR2: AFVALID2S Position */ -#define TPI_ITATBCTR2_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID2S_Pos) /*!< TPI ITATBCTR2: AFVALID2SS Mask */ - -#define TPI_ITATBCTR2_AFVALID1S_Pos 1U /*!< TPI ITATBCTR2: AFVALID1S Position */ -#define TPI_ITATBCTR2_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID1S_Pos) /*!< TPI ITATBCTR2: AFVALID1SS Mask */ - -#define TPI_ITATBCTR2_ATREADY2S_Pos 0U /*!< TPI ITATBCTR2: ATREADY2S Position */ -#define TPI_ITATBCTR2_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2S_Pos*/) /*!< TPI ITATBCTR2: ATREADY2S Mask */ - -#define TPI_ITATBCTR2_ATREADY1S_Pos 0U /*!< TPI ITATBCTR2: ATREADY1S Position */ -#define TPI_ITATBCTR2_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1S_Pos*/) /*!< TPI ITATBCTR2: ATREADY1S Mask */ - -/* TPI Integration Test FIFO Test Data 1 Register Definitions */ -#define TPI_ITFTTD1_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Position */ -#define TPI_ITFTTD1_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Mask */ - -#define TPI_ITFTTD1_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD1: ATB Interface 2 byte count Position */ -#define TPI_ITFTTD1_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 2 byte count Mask */ - -#define TPI_ITFTTD1_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Position */ -#define TPI_ITFTTD1_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Mask */ - -#define TPI_ITFTTD1_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD1: ATB Interface 1 byte count Position */ -#define TPI_ITFTTD1_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 1 byte countt Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data2_Pos 16U /*!< TPI ITFTTD1: ATB Interface 2 data2 Position */ -#define TPI_ITFTTD1_ATB_IF2_data2_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data2 Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data1_Pos 8U /*!< TPI ITFTTD1: ATB Interface 2 data1 Position */ -#define TPI_ITFTTD1_ATB_IF2_data1_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data1 Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data0_Pos 0U /*!< TPI ITFTTD1: ATB Interface 2 data0 Position */ -#define TPI_ITFTTD1_ATB_IF2_data0_Msk (0xFFUL /*<< TPI_ITFTTD1_ATB_IF2_data0_Pos*/) /*!< TPI ITFTTD1: ATB Interface 2 data0 Mask */ - -/* TPI Integration Test ATB Control Register 0 Definitions */ -#define TPI_ITATBCTR0_AFVALID2S_Pos 1U /*!< TPI ITATBCTR0: AFVALID2S Position */ -#define TPI_ITATBCTR0_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID2S_Pos) /*!< TPI ITATBCTR0: AFVALID2SS Mask */ - -#define TPI_ITATBCTR0_AFVALID1S_Pos 1U /*!< TPI ITATBCTR0: AFVALID1S Position */ -#define TPI_ITATBCTR0_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID1S_Pos) /*!< TPI ITATBCTR0: AFVALID1SS Mask */ - -#define TPI_ITATBCTR0_ATREADY2S_Pos 0U /*!< TPI ITATBCTR0: ATREADY2S Position */ -#define TPI_ITATBCTR0_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2S_Pos*/) /*!< TPI ITATBCTR0: ATREADY2S Mask */ - -#define TPI_ITATBCTR0_ATREADY1S_Pos 0U /*!< TPI ITATBCTR0: ATREADY1S Position */ -#define TPI_ITATBCTR0_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1S_Pos*/) /*!< TPI ITATBCTR0: ATREADY1S Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFOSZ Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFOSZ Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x3FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - uint32_t RESERVED0[7U]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#endif -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register */ -#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ -#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else -/*#define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping not available for Cortex-M23 */ -/*#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping not available for Cortex-M23 */ - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM23_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm23.h + * @brief CMSIS Cortex-M23 Core Peripheral Access Layer Header File + * @version V5.0.7 + * @date 22. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM23_H_GENERIC +#define __CORE_CM23_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M23 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS definitions */ +#define __CM23_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM23_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM23_CMSIS_VERSION ((__CM23_CMSIS_VERSION_MAIN << 16U) | \ + __CM23_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (23U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM23_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM23_H_DEPENDANT +#define __CORE_CM23_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM23_REV + #define __CM23_REV 0x0000U + #warning "__CM23_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __SAUREGION_PRESENT + #define __SAUREGION_PRESENT 0U + #warning "__SAUREGION_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __VTOR_PRESENT + #define __VTOR_PRESENT 0U + #warning "__VTOR_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif + + #ifndef __ETM_PRESENT + #define __ETM_PRESENT 0U + #warning "__ETM_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MTB_PRESENT + #define __MTB_PRESENT 0U + #warning "__MTB_PRESENT not defined in device header file; using default!" + #endif + +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M23 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core SAU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[16U]; + __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[16U]; + __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[16U]; + __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[16U]; + __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[16U]; + __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ + uint32_t RESERVED5[16U]; + __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ +#else + uint32_t RESERVED0; +#endif + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ +#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ + +#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ +#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ + +#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ +#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ +#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ +#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ + +#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ +#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ + +#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ +#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ +#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ + +#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ +#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ +#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ +#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ + +#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ +#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + uint32_t RESERVED0[6U]; + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + uint32_t RESERVED3[1U]; + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED4[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + uint32_t RESERVED5[1U]; + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED6[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + uint32_t RESERVED7[1U]; + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ + uint32_t RESERVED8[1U]; + __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ + uint32_t RESERVED9[1U]; + __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ + uint32_t RESERVED10[1U]; + __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ + uint32_t RESERVED11[1U]; + __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ + uint32_t RESERVED12[1U]; + __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ + uint32_t RESERVED13[1U]; + __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ + uint32_t RESERVED14[1U]; + __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ + uint32_t RESERVED15[1U]; + __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ + uint32_t RESERVED16[1U]; + __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ + uint32_t RESERVED17[1U]; + __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ + uint32_t RESERVED18[1U]; + __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ + uint32_t RESERVED19[1U]; + __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ + uint32_t RESERVED20[1U]; + __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ + uint32_t RESERVED21[1U]; + __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ + uint32_t RESERVED22[1U]; + __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ + uint32_t RESERVED23[1U]; + __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ + uint32_t RESERVED24[1U]; + __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ + uint32_t RESERVED25[1U]; + __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ + uint32_t RESERVED26[1U]; + __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ + uint32_t RESERVED27[1U]; + __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ + uint32_t RESERVED28[1U]; + __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ + uint32_t RESERVED29[1U]; + __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ + uint32_t RESERVED30[1U]; + __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ + uint32_t RESERVED31[1U]; + __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ +#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ + +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ +#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ + +#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ +#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t ITFTTD0; /*!< Offset: 0xEEC (R/ ) Integration Test FIFO Test Data 0 Register */ + __IOM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/W) Integration Test ATB Control Register 2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) Integration Test ATB Control Register 0 */ + __IM uint32_t ITFTTD1; /*!< Offset: 0xEFC (R/ ) Integration Test FIFO Test Data 1 Register */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) Device Configuration Register */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Identifier Register */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ +#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration Test FIFO Test Data 0 Register Definitions */ +#define TPI_ITFTTD0_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD0: ATB Interface 2 ATVALIDPosition */ +#define TPI_ITFTTD0_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 2 ATVALID Mask */ + +#define TPI_ITFTTD0_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD0: ATB Interface 2 byte count Position */ +#define TPI_ITFTTD0_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 2 byte count Mask */ + +#define TPI_ITFTTD0_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Position */ +#define TPI_ITFTTD0_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Mask */ + +#define TPI_ITFTTD0_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD0: ATB Interface 1 byte count Position */ +#define TPI_ITFTTD0_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 1 byte countt Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data2_Pos 16U /*!< TPI ITFTTD0: ATB Interface 1 data2 Position */ +#define TPI_ITFTTD0_ATB_IF1_data2_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data2 Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data1_Pos 8U /*!< TPI ITFTTD0: ATB Interface 1 data1 Position */ +#define TPI_ITFTTD0_ATB_IF1_data1_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data1 Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data0_Pos 0U /*!< TPI ITFTTD0: ATB Interface 1 data0 Position */ +#define TPI_ITFTTD0_ATB_IF1_data0_Msk (0xFFUL /*<< TPI_ITFTTD0_ATB_IF1_data0_Pos*/) /*!< TPI ITFTTD0: ATB Interface 1 data0 Mask */ + +/* TPI Integration Test ATB Control Register 2 Register Definitions */ +#define TPI_ITATBCTR2_AFVALID2S_Pos 1U /*!< TPI ITATBCTR2: AFVALID2S Position */ +#define TPI_ITATBCTR2_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID2S_Pos) /*!< TPI ITATBCTR2: AFVALID2SS Mask */ + +#define TPI_ITATBCTR2_AFVALID1S_Pos 1U /*!< TPI ITATBCTR2: AFVALID1S Position */ +#define TPI_ITATBCTR2_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID1S_Pos) /*!< TPI ITATBCTR2: AFVALID1SS Mask */ + +#define TPI_ITATBCTR2_ATREADY2S_Pos 0U /*!< TPI ITATBCTR2: ATREADY2S Position */ +#define TPI_ITATBCTR2_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2S_Pos*/) /*!< TPI ITATBCTR2: ATREADY2S Mask */ + +#define TPI_ITATBCTR2_ATREADY1S_Pos 0U /*!< TPI ITATBCTR2: ATREADY1S Position */ +#define TPI_ITATBCTR2_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1S_Pos*/) /*!< TPI ITATBCTR2: ATREADY1S Mask */ + +/* TPI Integration Test FIFO Test Data 1 Register Definitions */ +#define TPI_ITFTTD1_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Position */ +#define TPI_ITFTTD1_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Mask */ + +#define TPI_ITFTTD1_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD1: ATB Interface 2 byte count Position */ +#define TPI_ITFTTD1_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 2 byte count Mask */ + +#define TPI_ITFTTD1_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Position */ +#define TPI_ITFTTD1_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Mask */ + +#define TPI_ITFTTD1_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD1: ATB Interface 1 byte count Position */ +#define TPI_ITFTTD1_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 1 byte countt Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data2_Pos 16U /*!< TPI ITFTTD1: ATB Interface 2 data2 Position */ +#define TPI_ITFTTD1_ATB_IF2_data2_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data2 Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data1_Pos 8U /*!< TPI ITFTTD1: ATB Interface 2 data1 Position */ +#define TPI_ITFTTD1_ATB_IF2_data1_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data1 Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data0_Pos 0U /*!< TPI ITFTTD1: ATB Interface 2 data0 Position */ +#define TPI_ITFTTD1_ATB_IF2_data0_Msk (0xFFUL /*<< TPI_ITFTTD1_ATB_IF2_data0_Pos*/) /*!< TPI ITFTTD1: ATB Interface 2 data0 Mask */ + +/* TPI Integration Test ATB Control Register 0 Definitions */ +#define TPI_ITATBCTR0_AFVALID2S_Pos 1U /*!< TPI ITATBCTR0: AFVALID2S Position */ +#define TPI_ITATBCTR0_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID2S_Pos) /*!< TPI ITATBCTR0: AFVALID2SS Mask */ + +#define TPI_ITATBCTR0_AFVALID1S_Pos 1U /*!< TPI ITATBCTR0: AFVALID1S Position */ +#define TPI_ITATBCTR0_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID1S_Pos) /*!< TPI ITATBCTR0: AFVALID1SS Mask */ + +#define TPI_ITATBCTR0_ATREADY2S_Pos 0U /*!< TPI ITATBCTR0: ATREADY2S Position */ +#define TPI_ITATBCTR0_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2S_Pos*/) /*!< TPI ITATBCTR0: ATREADY2S Mask */ + +#define TPI_ITATBCTR0_ATREADY1S_Pos 0U /*!< TPI ITATBCTR0: ATREADY1S Position */ +#define TPI_ITATBCTR0_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1S_Pos*/) /*!< TPI ITATBCTR0: ATREADY1S Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFOSZ Position */ +#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFOSZ Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x3FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ + uint32_t RESERVED0[7U]; + union { + __IOM uint32_t MAIR[2]; + struct { + __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ + __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ + }; + }; +} MPU_Type; + +#define MPU_TYPE_RALIASES 1U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ +#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ + +#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ +#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ + +#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ +#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ + +#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ +#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ + +/* MPU Region Limit Address Register Definitions */ +#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ +#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ + +#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ +#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ + +#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ +#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ + +/* MPU Memory Attribute Indirection Register 0 Definitions */ +#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ +#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ + +#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ +#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ + +#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ +#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ + +#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ +#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ + +/* MPU Memory Attribute Indirection Register 1 Definitions */ +#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ +#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ + +#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ +#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ + +#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ +#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ + +#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ +#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SAU Security Attribution Unit (SAU) + \brief Type definitions for the Security Attribution Unit (SAU) + @{ + */ + +/** + \brief Structure type to access the Security Attribution Unit (SAU). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ + __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ +#endif +} SAU_Type; + +/* SAU Control Register Definitions */ +#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ +#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ + +#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ +#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ + +/* SAU Type Register Definitions */ +#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ +#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ + +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) +/* SAU Region Number Register Definitions */ +#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ +#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ + +/* SAU Region Base Address Register Definitions */ +#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ +#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ + +/* SAU Region Limit Address Register Definitions */ +#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ +#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ + +#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ +#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ + +#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ +#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ + +#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ + +/*@} end of group CMSIS_SAU */ +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ + uint32_t RESERVED4[1U]; + __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ + __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ +#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ +#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/* Debug Authentication Control Register Definitions */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ + +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ + +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ + +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ + +/* Debug Security Control and Status Register Definitions */ +#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ +#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ + +#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ +#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ + +#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ +#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ + #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ + #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ + #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ + #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ + #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ + #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ + #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + + + #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ + #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ + #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ + #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ + #endif + + #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ + #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ + #endif + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ + #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ + #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ + #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ + #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ + + #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ + #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ + #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ + #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ + #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ + #endif + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else +/*#define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping not available for Cortex-M23 */ +/*#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping not available for Cortex-M23 */ + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* Special LR values for Secure/Non-Secure call handling and exception handling */ + +/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ +#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ + +/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ +#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ +#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ +#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ +#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ +#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ +#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ +#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ + +/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ +#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ +#else +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ +#endif + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + +#define __NVIC_SetPriorityGrouping(X) (void)(X) +#define __NVIC_GetPriorityGrouping() (0U) + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Get Interrupt Target State + \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + \return 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Target State + \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Clear Interrupt Target State + \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + If VTOR is not present address 0 must be mapped to SRAM. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ +#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) + uint32_t *vectors = (uint32_t *)SCB->VTOR; +#else + uint32_t *vectors = (uint32_t *)0x0U; +#endif + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Enable Interrupt (non-secure) + \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status (non-secure) + \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt (non-secure) + \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Pending Interrupt (non-secure) + \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt (non-secure) + \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt (non-secure) + \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt (non-secure) + \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority (non-secure) + \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every non-secure processor exception. + */ +__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority (non-secure) + \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv8.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ########################## SAU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SAUFunctions SAU Functions + \brief Functions that configure the SAU. + @{ + */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + +/** + \brief Enable SAU + \details Enables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Enable(void) +{ + SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); +} + + + +/** + \brief Disable SAU + \details Disables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Disable(void) +{ + SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); +} + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_SAUFunctions */ + + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief System Tick Configuration (non-secure) + \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM23_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm3.h b/Drivers/CMSIS/Include/core_cm3.h index 74bff64..b0dfbd3 100644 --- a/Drivers/CMSIS/Include/core_cm3.h +++ b/Drivers/CMSIS/Include/core_cm3.h @@ -1,1941 +1,1941 @@ -/**************************************************************************//** - * @file core_cm3.h - * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File - * @version V5.0.8 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM3_H_GENERIC -#define __CORE_CM3_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M3 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM3 definitions */ -#define __CM3_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM3_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16U) | \ - __CM3_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (3U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM3_H_DEPENDANT -#define __CORE_CM3_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM3_REV - #define __CM3_REV 0x0200U - #warning "__CM3_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M3 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#if defined (__CM3_REV) && (__CM3_REV < 0x0201U) /* core r2p1 */ -#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ -#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ - -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#else -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ -#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -#else - uint32_t RESERVED1[1U]; -#endif -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V5.0.8 + * @date 04. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM3_H_GENERIC +#define __CORE_CM3_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M3 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM3 definitions */ +#define __CM3_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16U) | \ + __CM3_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (3U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM3_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM3_H_DEPENDANT +#define __CORE_CM3_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM3_REV + #define __CM3_REV 0x0200U + #warning "__CM3_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M3 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#if defined (__CM3_REV) && (__CM3_REV < 0x0201U) /* core r2p1 */ +#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#else +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ +#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +#else + uint32_t RESERVED1[1U]; +#endif +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM3_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm33.h b/Drivers/CMSIS/Include/core_cm33.h index 6cd2db7..02f82e2 100644 --- a/Drivers/CMSIS/Include/core_cm33.h +++ b/Drivers/CMSIS/Include/core_cm33.h @@ -1,3002 +1,3002 @@ -/**************************************************************************//** - * @file core_cm33.h - * @brief CMSIS Cortex-M33 Core Peripheral Access Layer Header File - * @version V5.0.9 - * @date 06. July 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM33_H_GENERIC -#define __CORE_CM33_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M33 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM33 definitions */ -#define __CM33_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM33_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM33_CMSIS_VERSION ((__CM33_CMSIS_VERSION_MAIN << 16U) | \ - __CM33_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (33U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined (__TARGET_FPU_VFP) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) - #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined (__ARM_PCS_VFP) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) - #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) - #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined (__ARMVFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) - #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined (__TI_VFP_SUPPORT__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined (__FPU_VFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM33_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM33_H_DEPENDANT -#define __CORE_CM33_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM33_REV - #define __CM33_REV 0x0000U - #warning "__CM33_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DSP_PRESENT - #define __DSP_PRESENT 0U - #warning "__DSP_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M33 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ -#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ - uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ - uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ -#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ - -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED6[580U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ - uint32_t RESERVED3[92U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ -#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ -#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ - -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ -#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ -#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Non-Secure Access Control Register Definitions */ -#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ -#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ - -#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ -#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ - -#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ -#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ - __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ - uint32_t RESERVED6[4U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Stimulus Port Register Definitions */ -#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ -#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ - -#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ -#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ -#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ - -#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ -#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ - uint32_t RESERVED32[934U]; - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ - uint32_t RESERVED33[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ -#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t ITFTTD0; /*!< Offset: 0xEEC (R/ ) Integration Test FIFO Test Data 0 Register */ - __IOM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/W) Integration Test ATB Control Register 2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) Integration Test ATB Control Register 0 */ - __IM uint32_t ITFTTD1; /*!< Offset: 0xEFC (R/ ) Integration Test FIFO Test Data 1 Register */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) Device Configuration Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Identifier Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration Test FIFO Test Data 0 Register Definitions */ -#define TPI_ITFTTD0_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD0: ATB Interface 2 ATVALIDPosition */ -#define TPI_ITFTTD0_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 2 ATVALID Mask */ - -#define TPI_ITFTTD0_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD0: ATB Interface 2 byte count Position */ -#define TPI_ITFTTD0_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 2 byte count Mask */ - -#define TPI_ITFTTD0_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Position */ -#define TPI_ITFTTD0_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Mask */ - -#define TPI_ITFTTD0_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD0: ATB Interface 1 byte count Position */ -#define TPI_ITFTTD0_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 1 byte countt Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data2_Pos 16U /*!< TPI ITFTTD0: ATB Interface 1 data2 Position */ -#define TPI_ITFTTD0_ATB_IF1_data2_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data2 Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data1_Pos 8U /*!< TPI ITFTTD0: ATB Interface 1 data1 Position */ -#define TPI_ITFTTD0_ATB_IF1_data1_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data1 Mask */ - -#define TPI_ITFTTD0_ATB_IF1_data0_Pos 0U /*!< TPI ITFTTD0: ATB Interface 1 data0 Position */ -#define TPI_ITFTTD0_ATB_IF1_data0_Msk (0xFFUL /*<< TPI_ITFTTD0_ATB_IF1_data0_Pos*/) /*!< TPI ITFTTD0: ATB Interface 1 data0 Mask */ - -/* TPI Integration Test ATB Control Register 2 Register Definitions */ -#define TPI_ITATBCTR2_AFVALID2S_Pos 1U /*!< TPI ITATBCTR2: AFVALID2S Position */ -#define TPI_ITATBCTR2_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID2S_Pos) /*!< TPI ITATBCTR2: AFVALID2SS Mask */ - -#define TPI_ITATBCTR2_AFVALID1S_Pos 1U /*!< TPI ITATBCTR2: AFVALID1S Position */ -#define TPI_ITATBCTR2_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID1S_Pos) /*!< TPI ITATBCTR2: AFVALID1SS Mask */ - -#define TPI_ITATBCTR2_ATREADY2S_Pos 0U /*!< TPI ITATBCTR2: ATREADY2S Position */ -#define TPI_ITATBCTR2_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2S_Pos*/) /*!< TPI ITATBCTR2: ATREADY2S Mask */ - -#define TPI_ITATBCTR2_ATREADY1S_Pos 0U /*!< TPI ITATBCTR2: ATREADY1S Position */ -#define TPI_ITATBCTR2_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1S_Pos*/) /*!< TPI ITATBCTR2: ATREADY1S Mask */ - -/* TPI Integration Test FIFO Test Data 1 Register Definitions */ -#define TPI_ITFTTD1_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Position */ -#define TPI_ITFTTD1_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Mask */ - -#define TPI_ITFTTD1_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD1: ATB Interface 2 byte count Position */ -#define TPI_ITFTTD1_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 2 byte count Mask */ - -#define TPI_ITFTTD1_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Position */ -#define TPI_ITFTTD1_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Mask */ - -#define TPI_ITFTTD1_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD1: ATB Interface 1 byte count Position */ -#define TPI_ITFTTD1_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 1 byte countt Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data2_Pos 16U /*!< TPI ITFTTD1: ATB Interface 2 data2 Position */ -#define TPI_ITFTTD1_ATB_IF2_data2_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data2 Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data1_Pos 8U /*!< TPI ITFTTD1: ATB Interface 2 data1 Position */ -#define TPI_ITFTTD1_ATB_IF2_data1_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data1 Mask */ - -#define TPI_ITFTTD1_ATB_IF2_data0_Pos 0U /*!< TPI ITFTTD1: ATB Interface 2 data0 Position */ -#define TPI_ITFTTD1_ATB_IF2_data0_Msk (0xFFUL /*<< TPI_ITFTTD1_ATB_IF2_data0_Pos*/) /*!< TPI ITFTTD1: ATB Interface 2 data0 Mask */ - -/* TPI Integration Test ATB Control Register 0 Definitions */ -#define TPI_ITATBCTR0_AFVALID2S_Pos 1U /*!< TPI ITATBCTR0: AFVALID2S Position */ -#define TPI_ITATBCTR0_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID2S_Pos) /*!< TPI ITATBCTR0: AFVALID2SS Mask */ - -#define TPI_ITATBCTR0_AFVALID1S_Pos 1U /*!< TPI ITATBCTR0: AFVALID1S Position */ -#define TPI_ITATBCTR0_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID1S_Pos) /*!< TPI ITATBCTR0: AFVALID1SS Mask */ - -#define TPI_ITATBCTR0_ATREADY2S_Pos 0U /*!< TPI ITATBCTR0: ATREADY2S Position */ -#define TPI_ITATBCTR0_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2S_Pos*/) /*!< TPI ITATBCTR0: ATREADY2S Mask */ - -#define TPI_ITATBCTR0_ATREADY1S_Pos 0U /*!< TPI ITATBCTR0: ATREADY1S Position */ -#define TPI_ITATBCTR0_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1S_Pos*/) /*!< TPI ITATBCTR0: ATREADY1S Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFOSZ Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFOSZ Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x3FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ - __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ - __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ - __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ - uint32_t RESERVED0[1]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#else - uint32_t RESERVED0[3]; -#endif - __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ - __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/* Secure Fault Status Register Definitions */ -#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ -#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ - -#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ -#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ - -#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ -#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ - -#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ -#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ - -#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ -#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ - -#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ -#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ - -#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ -#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ - -#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ -#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ -#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ - -#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ -#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ - -#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ -#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ - -#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ -#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ - -#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ -#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ - -#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ -#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ -#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ -#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - - #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ - #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - - #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ - #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Grouping (non-secure) - \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB_NS->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB_NS->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping (non-secure) - \details Reads the priority grouping field from the non-secure NVIC when in secure state. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) -{ - return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM33_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm33.h + * @brief CMSIS Cortex-M33 Core Peripheral Access Layer Header File + * @version V5.0.9 + * @date 06. July 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM33_H_GENERIC +#define __CORE_CM33_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M33 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM33 definitions */ +#define __CM33_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM33_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM33_CMSIS_VERSION ((__CM33_CMSIS_VERSION_MAIN << 16U) | \ + __CM33_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (33U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined (__TARGET_FPU_VFP) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) + #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined (__ARM_PCS_VFP) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) + #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) + #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined (__ARMVFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + + #if defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1U) + #if defined (__DSP_PRESENT) && (__DSP_PRESENT == 1U) + #define __DSP_USED 1U + #else + #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" + #define __DSP_USED 0U + #endif + #else + #define __DSP_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined (__TI_VFP_SUPPORT__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined (__FPU_VFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM33_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM33_H_DEPENDANT +#define __CORE_CM33_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM33_REV + #define __CM33_REV 0x0000U + #warning "__CM33_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __SAUREGION_PRESENT + #define __SAUREGION_PRESENT 0U + #warning "__SAUREGION_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DSP_PRESENT + #define __DSP_PRESENT 0U + #warning "__DSP_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M33 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core SAU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ + uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ + uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ + uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ +#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ + +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[16U]; + __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[16U]; + __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[16U]; + __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[16U]; + __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[16U]; + __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ + uint32_t RESERVED5[16U]; + __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED6[580U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ + __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ + __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ + __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ + uint32_t RESERVED3[92U]; + __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ + uint32_t RESERVED4[15U]; + __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ + uint32_t RESERVED5[1U]; + __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ + uint32_t RESERVED6[1U]; + __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ + __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ + __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ + __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ + __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ + __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ + __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ + __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ + uint32_t RESERVED7[6U]; + __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ + __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ + __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ + __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ + __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ + uint32_t RESERVED8[1U]; + __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ +#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ + +#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ +#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ + +#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ +#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ +#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ +#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ + +#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ +#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ +#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ +#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ + +#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ +#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ +#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ + +#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ +#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ + +#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ +#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ + +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ +#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ + +#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ +#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ +#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ +#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/* SCB Non-Secure Access Control Register Definitions */ +#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ +#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ + +#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ +#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ + +#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ +#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ + +/* SCB Cache Level ID Register Definitions */ +#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ +#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ + +#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ +#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ + +/* SCB Cache Type Register Definitions */ +#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ +#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ + +#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ +#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ + +#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ +#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ + +#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ +#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ + +#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ +#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ + +/* SCB Cache Size ID Register Definitions */ +#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ +#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ + +#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ +#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ + +#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ +#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ + +#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ +#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ + +#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ +#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ + +#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ +#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ + +#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ +#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ + +/* SCB Cache Size Selection Register Definitions */ +#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ +#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ + +#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ +#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ + +/* SCB Software Triggered Interrupt Register Definitions */ +#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ +#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ + +/* SCB D-Cache Invalidate by Set-way Register Definitions */ +#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ +#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ + +#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ +#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ + +/* SCB D-Cache Clean by Set-way Register Definitions */ +#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ +#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ + +#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ +#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ + +/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ +#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ +#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ + +#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ +#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ + +/* Instruction Tightly-Coupled Memory Control Register Definitions */ +#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ +#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ + +#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ +#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ + +#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ +#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ + +#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ +#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ + +/* Data Tightly-Coupled Memory Control Register Definitions */ +#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ +#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ + +#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ +#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ + +#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ +#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ + +#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ +#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ + +/* AHBP Control Register Definitions */ +#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ +#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ + +#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ +#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ + +/* L1 Cache Control Register Definitions */ +#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ +#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ + +#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ +#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ + +#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ +#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ + +/* AHBS Control Register Definitions */ +#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ +#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ + +#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ +#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ + +#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ +#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ + +/* Auxiliary Bus Fault Status Register Definitions */ +#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ +#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ + +#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ +#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ + +#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ +#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ + +#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ +#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ + +#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ +#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ + +#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ +#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ + __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[1U]; + __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ + uint32_t RESERVED6[4U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Stimulus Port Register Definitions */ +#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ +#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ + +#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ +#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ +#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ + +#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ +#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + uint32_t RESERVED3[1U]; + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED4[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + uint32_t RESERVED5[1U]; + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED6[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + uint32_t RESERVED7[1U]; + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ + uint32_t RESERVED8[1U]; + __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ + uint32_t RESERVED9[1U]; + __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ + uint32_t RESERVED10[1U]; + __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ + uint32_t RESERVED11[1U]; + __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ + uint32_t RESERVED12[1U]; + __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ + uint32_t RESERVED13[1U]; + __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ + uint32_t RESERVED14[1U]; + __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ + uint32_t RESERVED15[1U]; + __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ + uint32_t RESERVED16[1U]; + __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ + uint32_t RESERVED17[1U]; + __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ + uint32_t RESERVED18[1U]; + __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ + uint32_t RESERVED19[1U]; + __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ + uint32_t RESERVED20[1U]; + __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ + uint32_t RESERVED21[1U]; + __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ + uint32_t RESERVED22[1U]; + __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ + uint32_t RESERVED23[1U]; + __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ + uint32_t RESERVED24[1U]; + __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ + uint32_t RESERVED25[1U]; + __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ + uint32_t RESERVED26[1U]; + __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ + uint32_t RESERVED27[1U]; + __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ + uint32_t RESERVED28[1U]; + __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ + uint32_t RESERVED29[1U]; + __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ + uint32_t RESERVED30[1U]; + __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ + uint32_t RESERVED31[1U]; + __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ + uint32_t RESERVED32[934U]; + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ + uint32_t RESERVED33[1U]; + __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ +#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ +#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ + +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ +#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ + +#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ +#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t ITFTTD0; /*!< Offset: 0xEEC (R/ ) Integration Test FIFO Test Data 0 Register */ + __IOM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/W) Integration Test ATB Control Register 2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) Integration Test ATB Control Register 0 */ + __IM uint32_t ITFTTD1; /*!< Offset: 0xEFC (R/ ) Integration Test FIFO Test Data 1 Register */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) Device Configuration Register */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Identifier Register */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ +#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration Test FIFO Test Data 0 Register Definitions */ +#define TPI_ITFTTD0_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD0: ATB Interface 2 ATVALIDPosition */ +#define TPI_ITFTTD0_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 2 ATVALID Mask */ + +#define TPI_ITFTTD0_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD0: ATB Interface 2 byte count Position */ +#define TPI_ITFTTD0_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 2 byte count Mask */ + +#define TPI_ITFTTD0_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Position */ +#define TPI_ITFTTD0_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD0: ATB Interface 1 ATVALID Mask */ + +#define TPI_ITFTTD0_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD0: ATB Interface 1 byte count Position */ +#define TPI_ITFTTD0_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD0_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD0: ATB Interface 1 byte countt Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data2_Pos 16U /*!< TPI ITFTTD0: ATB Interface 1 data2 Position */ +#define TPI_ITFTTD0_ATB_IF1_data2_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data2 Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data1_Pos 8U /*!< TPI ITFTTD0: ATB Interface 1 data1 Position */ +#define TPI_ITFTTD0_ATB_IF1_data1_Msk (0xFFUL << TPI_ITFTTD0_ATB_IF1_data1_Pos) /*!< TPI ITFTTD0: ATB Interface 1 data1 Mask */ + +#define TPI_ITFTTD0_ATB_IF1_data0_Pos 0U /*!< TPI ITFTTD0: ATB Interface 1 data0 Position */ +#define TPI_ITFTTD0_ATB_IF1_data0_Msk (0xFFUL /*<< TPI_ITFTTD0_ATB_IF1_data0_Pos*/) /*!< TPI ITFTTD0: ATB Interface 1 data0 Mask */ + +/* TPI Integration Test ATB Control Register 2 Register Definitions */ +#define TPI_ITATBCTR2_AFVALID2S_Pos 1U /*!< TPI ITATBCTR2: AFVALID2S Position */ +#define TPI_ITATBCTR2_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID2S_Pos) /*!< TPI ITATBCTR2: AFVALID2SS Mask */ + +#define TPI_ITATBCTR2_AFVALID1S_Pos 1U /*!< TPI ITATBCTR2: AFVALID1S Position */ +#define TPI_ITATBCTR2_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR2_AFVALID1S_Pos) /*!< TPI ITATBCTR2: AFVALID1SS Mask */ + +#define TPI_ITATBCTR2_ATREADY2S_Pos 0U /*!< TPI ITATBCTR2: ATREADY2S Position */ +#define TPI_ITATBCTR2_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2S_Pos*/) /*!< TPI ITATBCTR2: ATREADY2S Mask */ + +#define TPI_ITATBCTR2_ATREADY1S_Pos 0U /*!< TPI ITATBCTR2: ATREADY1S Position */ +#define TPI_ITATBCTR2_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1S_Pos*/) /*!< TPI ITATBCTR2: ATREADY1S Mask */ + +/* TPI Integration Test FIFO Test Data 1 Register Definitions */ +#define TPI_ITFTTD1_ATB_IF2_ATVALID_Pos 29U /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Position */ +#define TPI_ITFTTD1_ATB_IF2_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 2 ATVALID Mask */ + +#define TPI_ITFTTD1_ATB_IF2_bytecount_Pos 27U /*!< TPI ITFTTD1: ATB Interface 2 byte count Position */ +#define TPI_ITFTTD1_ATB_IF2_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF2_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 2 byte count Mask */ + +#define TPI_ITFTTD1_ATB_IF1_ATVALID_Pos 26U /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Position */ +#define TPI_ITFTTD1_ATB_IF1_ATVALID_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_ATVALID_Pos) /*!< TPI ITFTTD1: ATB Interface 1 ATVALID Mask */ + +#define TPI_ITFTTD1_ATB_IF1_bytecount_Pos 24U /*!< TPI ITFTTD1: ATB Interface 1 byte count Position */ +#define TPI_ITFTTD1_ATB_IF1_bytecount_Msk (0x3UL << TPI_ITFTTD1_ATB_IF1_bytecount_Pos) /*!< TPI ITFTTD1: ATB Interface 1 byte countt Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data2_Pos 16U /*!< TPI ITFTTD1: ATB Interface 2 data2 Position */ +#define TPI_ITFTTD1_ATB_IF2_data2_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data2 Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data1_Pos 8U /*!< TPI ITFTTD1: ATB Interface 2 data1 Position */ +#define TPI_ITFTTD1_ATB_IF2_data1_Msk (0xFFUL << TPI_ITFTTD1_ATB_IF2_data1_Pos) /*!< TPI ITFTTD1: ATB Interface 2 data1 Mask */ + +#define TPI_ITFTTD1_ATB_IF2_data0_Pos 0U /*!< TPI ITFTTD1: ATB Interface 2 data0 Position */ +#define TPI_ITFTTD1_ATB_IF2_data0_Msk (0xFFUL /*<< TPI_ITFTTD1_ATB_IF2_data0_Pos*/) /*!< TPI ITFTTD1: ATB Interface 2 data0 Mask */ + +/* TPI Integration Test ATB Control Register 0 Definitions */ +#define TPI_ITATBCTR0_AFVALID2S_Pos 1U /*!< TPI ITATBCTR0: AFVALID2S Position */ +#define TPI_ITATBCTR0_AFVALID2S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID2S_Pos) /*!< TPI ITATBCTR0: AFVALID2SS Mask */ + +#define TPI_ITATBCTR0_AFVALID1S_Pos 1U /*!< TPI ITATBCTR0: AFVALID1S Position */ +#define TPI_ITATBCTR0_AFVALID1S_Msk (0x1UL << TPI_ITATBCTR0_AFVALID1S_Pos) /*!< TPI ITATBCTR0: AFVALID1SS Mask */ + +#define TPI_ITATBCTR0_ATREADY2S_Pos 0U /*!< TPI ITATBCTR0: ATREADY2S Position */ +#define TPI_ITATBCTR0_ATREADY2S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2S_Pos*/) /*!< TPI ITATBCTR0: ATREADY2S Mask */ + +#define TPI_ITATBCTR0_ATREADY1S_Pos 0U /*!< TPI ITATBCTR0: ATREADY1S Position */ +#define TPI_ITATBCTR0_ATREADY1S_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1S_Pos*/) /*!< TPI ITATBCTR0: ATREADY1S Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFOSZ Position */ +#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFOSZ Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x3FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ + __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ + __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ + __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ + uint32_t RESERVED0[1]; + union { + __IOM uint32_t MAIR[2]; + struct { + __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ + __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ + }; + }; +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ +#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ + +#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ +#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ + +#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ +#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ + +#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ +#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ + +/* MPU Region Limit Address Register Definitions */ +#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ +#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ + +#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ +#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ + +#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ +#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ + +/* MPU Memory Attribute Indirection Register 0 Definitions */ +#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ +#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ + +#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ +#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ + +#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ +#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ + +#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ +#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ + +/* MPU Memory Attribute Indirection Register 1 Definitions */ +#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ +#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ + +#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ +#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ + +#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ +#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ + +#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ +#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SAU Security Attribution Unit (SAU) + \brief Type definitions for the Security Attribution Unit (SAU) + @{ + */ + +/** + \brief Structure type to access the Security Attribution Unit (SAU). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ + __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ + __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ +#else + uint32_t RESERVED0[3]; +#endif + __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ + __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ +} SAU_Type; + +/* SAU Control Register Definitions */ +#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ +#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ + +#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ +#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ + +/* SAU Type Register Definitions */ +#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ +#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ + +#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) +/* SAU Region Number Register Definitions */ +#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ +#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ + +/* SAU Region Base Address Register Definitions */ +#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ +#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ + +/* SAU Region Limit Address Register Definitions */ +#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ +#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ + +#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ +#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ + +#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ +#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ + +#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ + +/* Secure Fault Status Register Definitions */ +#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ +#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ + +#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ +#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ + +#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ +#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ + +#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ +#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ + +#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ +#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ + +#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ +#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ + +#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ +#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ + +#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ +#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ + +/*@} end of group CMSIS_SAU */ +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ +#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ + +#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ +#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ + +#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ +#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ + +#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ +#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ + +#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ +#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ + +#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ +#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ +#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ +#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ + uint32_t RESERVED4[1U]; + __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ + __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ +#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/* Debug Authentication Control Register Definitions */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ +#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ + +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ + +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ +#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ + +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ +#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ + +/* Debug Security Control and Status Register Definitions */ +#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ +#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ + +#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ +#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ + +#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ +#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ + #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ + #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ + #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ + #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ + #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ + #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ + #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ + #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + + #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ + #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ + #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ + #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ + #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ + #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ + #endif + + #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ + #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ + #endif + + #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ + #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ + #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ + #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ + #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ + #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ + + #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ + #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ + #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ + #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ + #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ + + #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ + #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ + #endif + + #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ + #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* Special LR values for Secure/Non-Secure call handling and exception handling */ + +/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ +#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ + +/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ +#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ +#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ +#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ +#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ +#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ +#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ +#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ + +/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ +#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ +#else +#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ +#endif + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Get Interrupt Target State + \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + \return 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Target State + \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Clear Interrupt Target State + \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 if interrupt is assigned to Secure + 1 if interrupt is assigned to Non Secure + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); + return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief Set Priority Grouping (non-secure) + \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB_NS->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB_NS->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping (non-secure) + \details Reads the priority grouping field from the non-secure NVIC when in secure state. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) +{ + return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt (non-secure) + \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status (non-secure) + \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt (non-secure) + \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Pending Interrupt (non-secure) + \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt (non-secure) + \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt (non-secure) + \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt (non-secure) + \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority (non-secure) + \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every non-secure processor exception. + */ +__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority (non-secure) + \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} +#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv8.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = FPU->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) + { + return 2U; /* Double + Single precision FPU */ + } + else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ########################## SAU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SAUFunctions SAU Functions + \brief Functions that configure the SAU. + @{ + */ + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) + +/** + \brief Enable SAU + \details Enables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Enable(void) +{ + SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); +} + + + +/** + \brief Disable SAU + \details Disables the Security Attribution Unit (SAU). + */ +__STATIC_INLINE void TZ_SAU_Disable(void) +{ + SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); +} + +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +/*@} end of CMSIS_Core_SAUFunctions */ + + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) +/** + \brief System Tick Configuration (non-secure) + \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} +#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM33_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm4.h b/Drivers/CMSIS/Include/core_cm4.h index 7d56873..308b868 100644 --- a/Drivers/CMSIS/Include/core_cm4.h +++ b/Drivers/CMSIS/Include/core_cm4.h @@ -1,2129 +1,2129 @@ -/**************************************************************************//** - * @file core_cm4.h - * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V5.0.8 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM4_H_GENERIC -#define __CORE_CM4_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M4 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM4 definitions */ -#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ - __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (4U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM4_H_DEPENDANT -#define __CORE_CM4_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM4_REV - #define __CM4_REV 0x0000U - #warning "__CM4_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M4 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V5.0.8 + * @date 04. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M4 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ + __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (4U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM4_REV + #define __CM4_REV 0x0000U + #warning "__CM4_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M4 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ +#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ +#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = FPU->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_cm7.h b/Drivers/CMSIS/Include/core_cm7.h index a14dc62..ada6c2a 100644 --- a/Drivers/CMSIS/Include/core_cm7.h +++ b/Drivers/CMSIS/Include/core_cm7.h @@ -1,2671 +1,2671 @@ -/**************************************************************************//** - * @file core_cm7.h - * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File - * @version V5.0.8 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM7_H_GENERIC -#define __CORE_CM7_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M7 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM7 definitions */ -#define __CM7_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM7_CMSIS_VERSION_SUB ( __CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM7_CMSIS_VERSION ((__CM7_CMSIS_VERSION_MAIN << 16U) | \ - __CM7_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (7U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM7_H_DEPENDANT -#define __CORE_CM7_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM7_REV - #define __CM7_REV 0x0000U - #warning "__CM7_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __ICACHE_PRESENT - #define __ICACHE_PRESENT 0U - #warning "__ICACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DCACHE_PRESENT - #define __DCACHE_PRESENT 0U - #warning "__DCACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DTCM_PRESENT - #define __DTCM_PRESENT 0U - #warning "__DTCM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M7 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_AFR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[1U]; - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - uint32_t RESERVED3[93U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: Branch prediction enable bit Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: Branch prediction enable bit Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: Instruction cache enable bit Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: Instruction cache enable bit Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: Cache enable bit Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: Cache enable bit Mask */ - -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12U /*!< ACTLR: DISITMATBFLUSH Position */ -#define SCnSCB_ACTLR_DISITMATBFLUSH_Msk (1UL << SCnSCB_ACTLR_DISITMATBFLUSH_Pos) /*!< ACTLR: DISITMATBFLUSH Mask */ - -#define SCnSCB_ACTLR_DISRAMODE_Pos 11U /*!< ACTLR: DISRAMODE Position */ -#define SCnSCB_ACTLR_DISRAMODE_Msk (1UL << SCnSCB_ACTLR_DISRAMODE_Pos) /*!< ACTLR: DISRAMODE Mask */ - -#define SCnSCB_ACTLR_FPEXCODIS_Pos 10U /*!< ACTLR: FPEXCODIS Position */ -#define SCnSCB_ACTLR_FPEXCODIS_Msk (1UL << SCnSCB_ACTLR_FPEXCODIS_Pos) /*!< ACTLR: FPEXCODIS Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED3[981U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( W) Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/* Media and FP Feature Register 2 Definitions */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = SCB->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## Cache functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_CacheFunctions Cache Functions - \brief Functions that configure Instruction and Data cache. - @{ - */ - -/* Cache Size ID Register Macros */ -#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) -#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) - - -/** - \brief Enable I-Cache - \details Turns on I-Cache - */ -__STATIC_INLINE void SCB_EnableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable I-Cache - \details Turns off I-Cache - */ -__STATIC_INLINE void SCB_DisableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */ - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate I-Cache - \details Invalidates I-Cache - */ -__STATIC_INLINE void SCB_InvalidateICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Enable D-Cache - \details Turns on D-Cache - */ -__STATIC_INLINE void SCB_EnableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - __DSB(); - - SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */ - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable D-Cache - \details Turns off D-Cache - */ -__STATIC_INLINE void SCB_DisableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ - __DSB(); - - SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate D-Cache - \details Invalidates D-Cache - */ -__STATIC_INLINE void SCB_InvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean D-Cache - \details Cleans D-Cache - */ -__STATIC_INLINE void SCB_CleanDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) | - ((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean & Invalidate D-Cache - \details Cleans and Invalidates D-Cache - */ -__STATIC_INLINE void SCB_CleanInvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief D-Cache Invalidate by address - \details Invalidates D-Cache for the given address - \param[in] addr address (aligned to 32-byte boundary) - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_INLINE void SCB_InvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - int32_t op_size = dsize; - uint32_t op_addr = (uint32_t)addr; - int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ - - __DSB(); - - while (op_size > 0) { - SCB->DCIMVAC = op_addr; - op_addr += (uint32_t)linesize; - op_size -= linesize; - } - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief D-Cache Clean by address - \details Cleans D-Cache for the given address - \param[in] addr address (aligned to 32-byte boundary) - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_INLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - int32_t op_size = dsize; - uint32_t op_addr = (uint32_t) addr; - int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ - - __DSB(); - - while (op_size > 0) { - SCB->DCCMVAC = op_addr; - op_addr += (uint32_t)linesize; - op_size -= linesize; - } - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief D-Cache Clean and Invalidate by address - \details Cleans and invalidates D_Cache for the given address - \param[in] addr address (aligned to 32-byte boundary) - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_INLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - int32_t op_size = dsize; - uint32_t op_addr = (uint32_t) addr; - int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ - - __DSB(); - - while (op_size > 0) { - SCB->DCCIMVAC = op_addr; - op_addr += (uint32_t)linesize; - op_size -= linesize; - } - - __DSB(); - __ISB(); - #endif -} - - -/*@} end of CMSIS_Core_CacheFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_cm7.h + * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File + * @version V5.0.8 + * @date 04. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM7_H_GENERIC +#define __CORE_CM7_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M7 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM7 definitions */ +#define __CM7_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM7_CMSIS_VERSION_SUB ( __CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM7_CMSIS_VERSION ((__CM7_CMSIS_VERSION_MAIN << 16U) | \ + __CM7_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (7U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM7_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM7_H_DEPENDANT +#define __CORE_CM7_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM7_REV + #define __CM7_REV 0x0000U + #warning "__CM7_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __ICACHE_PRESENT + #define __ICACHE_PRESENT 0U + #warning "__ICACHE_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DCACHE_PRESENT + #define __DCACHE_PRESENT 0U + #warning "__DCACHE_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DTCM_PRESENT + #define __DTCM_PRESENT 0U + #warning "__DTCM_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M7 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ID_AFR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t ID_MFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ID_ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[1U]; + __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ + __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ + __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ + __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + uint32_t RESERVED3[93U]; + __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ + uint32_t RESERVED4[15U]; + __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ + uint32_t RESERVED5[1U]; + __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ + uint32_t RESERVED6[1U]; + __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ + __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ + __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ + __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ + __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ + __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ + __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ + __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ + uint32_t RESERVED7[6U]; + __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ + __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ + __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ + __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ + __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ + uint32_t RESERVED8[1U]; + __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: Branch prediction enable bit Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: Branch prediction enable bit Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: Instruction cache enable bit Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: Instruction cache enable bit Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: Cache enable bit Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: Cache enable bit Mask */ + +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/* SCB Cache Level ID Register Definitions */ +#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ +#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ + +#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ +#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ + +/* SCB Cache Type Register Definitions */ +#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ +#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ + +#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ +#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ + +#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ +#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ + +#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ +#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ + +#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ +#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ + +/* SCB Cache Size ID Register Definitions */ +#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ +#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ + +#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ +#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ + +#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ +#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ + +#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ +#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ + +#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ +#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ + +#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ +#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ + +#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ +#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ + +/* SCB Cache Size Selection Register Definitions */ +#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ +#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ + +#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ +#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ + +/* SCB Software Triggered Interrupt Register Definitions */ +#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ +#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ + +/* SCB D-Cache Invalidate by Set-way Register Definitions */ +#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ +#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ + +#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ +#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ + +/* SCB D-Cache Clean by Set-way Register Definitions */ +#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ +#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ + +#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ +#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ + +/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ +#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ +#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ + +#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ +#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ + +/* Instruction Tightly-Coupled Memory Control Register Definitions */ +#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ +#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ + +#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ +#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ + +#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ +#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ + +#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ +#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ + +/* Data Tightly-Coupled Memory Control Register Definitions */ +#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ +#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ + +#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ +#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ + +#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ +#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ + +#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ +#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ + +/* AHBP Control Register Definitions */ +#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ +#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ + +#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ +#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ + +/* L1 Cache Control Register Definitions */ +#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ +#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ + +#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ +#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ + +#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ +#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ + +/* AHBS Control Register Definitions */ +#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ +#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ + +#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ +#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ + +#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ +#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ + +/* Auxiliary Bus Fault Status Register Definitions */ +#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ +#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ + +#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ +#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ + +#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ +#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ + +#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ +#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ + +#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ +#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ + +#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ +#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12U /*!< ACTLR: DISITMATBFLUSH Position */ +#define SCnSCB_ACTLR_DISITMATBFLUSH_Msk (1UL << SCnSCB_ACTLR_DISITMATBFLUSH_Pos) /*!< ACTLR: DISITMATBFLUSH Mask */ + +#define SCnSCB_ACTLR_DISRAMODE_Pos 11U /*!< ACTLR: DISRAMODE Position */ +#define SCnSCB_ACTLR_DISRAMODE_Msk (1UL << SCnSCB_ACTLR_DISRAMODE_Pos) /*!< ACTLR: DISRAMODE Mask */ + +#define SCnSCB_ACTLR_FPEXCODIS_Pos 10U /*!< ACTLR: FPEXCODIS Position */ +#define SCnSCB_ACTLR_FPEXCODIS_Msk (1UL << SCnSCB_ACTLR_FPEXCODIS_Pos) /*!< ACTLR: FPEXCODIS Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ + uint32_t RESERVED3[981U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( W) Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/* Media and FP Feature Register 2 Definitions */ + +/*@} end of group CMSIS_FPU */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ +#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ +#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = SCB->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) + { + return 2U; /* Double + Single precision FPU */ + } + else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ########################## Cache functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_CacheFunctions Cache Functions + \brief Functions that configure Instruction and Data cache. + @{ + */ + +/* Cache Size ID Register Macros */ +#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) +#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) + + +/** + \brief Enable I-Cache + \details Turns on I-Cache + */ +__STATIC_INLINE void SCB_EnableICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + __DSB(); + __ISB(); + SCB->ICIALLU = 0UL; /* invalidate I-Cache */ + __DSB(); + __ISB(); + SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */ + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Disable I-Cache + \details Turns off I-Cache + */ +__STATIC_INLINE void SCB_DisableICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + __DSB(); + __ISB(); + SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */ + SCB->ICIALLU = 0UL; /* invalidate I-Cache */ + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Invalidate I-Cache + \details Invalidates I-Cache + */ +__STATIC_INLINE void SCB_InvalidateICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + __DSB(); + __ISB(); + SCB->ICIALLU = 0UL; + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Enable D-Cache + \details Turns on D-Cache + */ +__STATIC_INLINE void SCB_EnableDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | + ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + __DSB(); + + SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */ + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Disable D-Cache + \details Turns off D-Cache + */ +__STATIC_INLINE void SCB_DisableDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ + __DSB(); + + SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean & invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | + ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Invalidate D-Cache + \details Invalidates D-Cache + */ +__STATIC_INLINE void SCB_InvalidateDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | + ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Clean D-Cache + \details Cleans D-Cache + */ +__STATIC_INLINE void SCB_CleanDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) | + ((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Clean & Invalidate D-Cache + \details Cleans and Invalidates D-Cache + */ +__STATIC_INLINE void SCB_CleanInvalidateDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /*(0U << 1U) | 0U;*/ /* Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean & invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | + ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief D-Cache Invalidate by address + \details Invalidates D-Cache for the given address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_InvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t)addr; + int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ + + __DSB(); + + while (op_size > 0) { + SCB->DCIMVAC = op_addr; + op_addr += (uint32_t)linesize; + op_size -= linesize; + } + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief D-Cache Clean by address + \details Cleans D-Cache for the given address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t) addr; + int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ + + __DSB(); + + while (op_size > 0) { + SCB->DCCMVAC = op_addr; + op_addr += (uint32_t)linesize; + op_size -= linesize; + } + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief D-Cache Clean and Invalidate by address + \details Cleans and invalidates D_Cache for the given address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t) addr; + int32_t linesize = 32; /* in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) */ + + __DSB(); + + while (op_size > 0) { + SCB->DCCIMVAC = op_addr; + op_addr += (uint32_t)linesize; + op_size -= linesize; + } + + __DSB(); + __ISB(); + #endif +} + + +/*@} end of CMSIS_Core_CacheFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM7_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_sc000.h b/Drivers/CMSIS/Include/core_sc000.h index 9b67c92..9086c64 100644 --- a/Drivers/CMSIS/Include/core_sc000.h +++ b/Drivers/CMSIS/Include/core_sc000.h @@ -1,1022 +1,1022 @@ -/**************************************************************************//** - * @file core_sc000.h - * @brief CMSIS SC000 Core Peripheral Access Layer Header File - * @version V5.0.5 - * @date 28. May 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_SC000_H_GENERIC -#define __CORE_SC000_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup SC000 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS SC000 definitions */ -#define __SC000_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __SC000_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __SC000_CMSIS_VERSION ((__SC000_CMSIS_VERSION_MAIN << 16U) | \ - __SC000_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_SC (000U) /*!< Cortex secure core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_SC000_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_SC000_H_DEPENDANT -#define __CORE_SC000_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __SC000_REV - #define __SC000_REV 0x0000U - #warning "__SC000_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group SC000 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t _reserved0:1; /*!< bit: 0 Reserved */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED0[1U]; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - uint32_t RESERVED1[154U]; - __IOM uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ -} MPU_Type; - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief SC000 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the SC000 header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else -/*#define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping not available for SC000 */ -/*#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping not available for SC000 */ - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for SC000 */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_SC000_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_sc000.h + * @brief CMSIS SC000 Core Peripheral Access Layer Header File + * @version V5.0.5 + * @date 28. May 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_SC000_H_GENERIC +#define __CORE_SC000_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup SC000 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS SC000 definitions */ +#define __SC000_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __SC000_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __SC000_CMSIS_VERSION ((__SC000_CMSIS_VERSION_MAIN << 16U) | \ + __SC000_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_SC (000U) /*!< Cortex secure core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_SC000_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_SC000_H_DEPENDANT +#define __CORE_SC000_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __SC000_REV + #define __SC000_REV 0x0000U + #warning "__SC000_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group SC000 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core MPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t _reserved0:1; /*!< bit: 0 Reserved */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31U]; + __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31U]; + __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31U]; + __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31U]; + uint32_t RESERVED4[64U]; + __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED0[1U]; + __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + uint32_t RESERVED1[154U]; + __IOM uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief SC000 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. + Therefore they are not covered by the SC000 header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else +/*#define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping not available for SC000 */ +/*#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping not available for SC000 */ + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ +/*#define NVIC_GetActive __NVIC_GetActive not available for SC000 */ + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + +/* Interrupt Priorities are WORD accessible only under Armv6-M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } + else + { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_SC000_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/core_sc300.h b/Drivers/CMSIS/Include/core_sc300.h index 3e8a471..665822d 100644 --- a/Drivers/CMSIS/Include/core_sc300.h +++ b/Drivers/CMSIS/Include/core_sc300.h @@ -1,1915 +1,1915 @@ -/**************************************************************************//** - * @file core_sc300.h - * @brief CMSIS SC300 Core Peripheral Access Layer Header File - * @version V5.0.6 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_SC300_H_GENERIC -#define __CORE_SC300_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup SC3000 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS SC300 definitions */ -#define __SC300_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __SC300_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __SC300_CMSIS_VERSION ((__SC300_CMSIS_VERSION_MAIN << 16U) | \ - __SC300_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_SC (300U) /*!< Cortex secure core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_SC300_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_SC300_H_DEPENDANT -#define __CORE_SC300_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __SC300_REV - #define __SC300_REV 0x0000U - #warning "__SC300_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group SC300 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - uint32_t RESERVED1[129U]; - __IOM uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ -#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ - -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - uint32_t RESERVED1[1U]; -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_SC300_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ +/**************************************************************************//** + * @file core_sc300.h + * @brief CMSIS SC300 Core Peripheral Access Layer Header File + * @version V5.0.6 + * @date 04. June 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_SC300_H_GENERIC +#define __CORE_SC300_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup SC3000 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS SC300 definitions */ +#define __SC300_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __SC300_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __SC300_CMSIS_VERSION ((__SC300_CMSIS_VERSION_MAIN << 16U) | \ + __SC300_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_SC (300U) /*!< Cortex secure core */ + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_SC300_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_SC300_H_DEPENDANT +#define __CORE_SC300_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __SC300_REV + #define __SC300_REV 0x0000U + #warning "__SC300_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group SC300 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + uint32_t RESERVED1[129U]; + __IOM uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + uint32_t RESERVED1[1U]; +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ + + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + return 0U; /* No FPU */ +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_SC300_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/Drivers/CMSIS/Include/mpu_armv7.h b/Drivers/CMSIS/Include/mpu_armv7.h index 0142203..7d4b600 100644 --- a/Drivers/CMSIS/Include/mpu_armv7.h +++ b/Drivers/CMSIS/Include/mpu_armv7.h @@ -1,270 +1,270 @@ -/****************************************************************************** - * @file mpu_armv7.h - * @brief CMSIS MPU API for Armv7-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV7_H -#define ARM_MPU_ARMV7_H - -#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes -#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes -#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes -#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes -#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes -#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte -#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes -#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes -#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes -#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes -#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes -#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes -#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes -#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes -#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes -#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte -#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes -#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes -#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes -#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes -#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes -#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes -#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes -#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes -#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes -#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte -#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes -#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes - -#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access -#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only -#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only -#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access -#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only -#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access - -/** MPU Region Base Address Register Value -* -* \param Region The region to be configured, number 0 to 15. -* \param BaseAddress The base address for the region. -*/ -#define ARM_MPU_RBAR(Region, BaseAddress) \ - (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ - ((Region) & MPU_RBAR_REGION_Msk) | \ - (MPU_RBAR_VALID_Msk)) - -/** -* MPU Memory Access Attributes -* -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -*/ -#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ - ((((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ - (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ - (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ - (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ - ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ - (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ - (((AccessAttributes) ) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ - ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) - -/** -* MPU Memory Access Attribute for strongly ordered memory. -* - TEX: 000b -* - Shareable -* - Non-cacheable -* - Non-bufferable -*/ -#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) - -/** -* MPU Memory Access Attribute for device memory. -* - TEX: 000b (if non-shareable) or 010b (if shareable) -* - Shareable or non-shareable -* - Non-cacheable -* - Bufferable (if shareable) or non-bufferable (if non-shareable) -* -* \param IsShareable Configures the device memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) - -/** -* MPU Memory Access Attribute for normal memory. -* - TEX: 1BBb (reflecting outer cacheability rules) -* - Shareable or non-shareable -* - Cacheable or non-cacheable (reflecting inner cacheability rules) -* - Bufferable or non-bufferable (reflecting inner cacheability rules) -* -* \param OuterCp Configures the outer cache policy. -* \param InnerCp Configures the inner cache policy. -* \param IsShareable Configures the memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) - -/** -* MPU Memory Access Attribute non-cacheable policy. -*/ -#define ARM_MPU_CACHEP_NOCACHE 0U - -/** -* MPU Memory Access Attribute write-back, write and read allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_WRA 1U - -/** -* MPU Memory Access Attribute write-through, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WT_NWA 2U - -/** -* MPU Memory Access Attribute write-back, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_NWA 3U - - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; //!< The region base address register value (RBAR) - uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - MPU->RNR = rnr; - MPU->RASR = 0U; -} - -/** Configure an MPU region. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) -{ - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) -{ - MPU->RNR = rnr; - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - while (cnt > MPU_TYPE_RALIASES) { - orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); - table += MPU_TYPE_RALIASES; - cnt -= MPU_TYPE_RALIASES; - } - orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); -} - -#endif +/****************************************************************************** + * @file mpu_armv7.h + * @brief CMSIS MPU API for Armv7-M MPU + * @version V5.0.4 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2017-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV7_H +#define ARM_MPU_ARMV7_H + +#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes +#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes +#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes +#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes +#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes +#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte +#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes +#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes +#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes +#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes +#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes +#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes +#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes +#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes +#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes +#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte +#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes +#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes +#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes +#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes +#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes +#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes +#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes +#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes +#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes +#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte +#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes +#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes + +#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access +#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only +#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only +#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access +#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only +#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access + +/** MPU Region Base Address Register Value +* +* \param Region The region to be configured, number 0 to 15. +* \param BaseAddress The base address for the region. +*/ +#define ARM_MPU_RBAR(Region, BaseAddress) \ + (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ + ((Region) & MPU_RBAR_REGION_Msk) | \ + (MPU_RBAR_VALID_Msk)) + +/** +* MPU Memory Access Attributes +* +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +*/ +#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ + ((((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ + (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ + (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ + (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ + ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ + (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ + (((AccessAttributes) ) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ + ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) + +/** +* MPU Memory Access Attribute for strongly ordered memory. +* - TEX: 000b +* - Shareable +* - Non-cacheable +* - Non-bufferable +*/ +#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) + +/** +* MPU Memory Access Attribute for device memory. +* - TEX: 000b (if non-shareable) or 010b (if shareable) +* - Shareable or non-shareable +* - Non-cacheable +* - Bufferable (if shareable) or non-bufferable (if non-shareable) +* +* \param IsShareable Configures the device memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) + +/** +* MPU Memory Access Attribute for normal memory. +* - TEX: 1BBb (reflecting outer cacheability rules) +* - Shareable or non-shareable +* - Cacheable or non-cacheable (reflecting inner cacheability rules) +* - Bufferable or non-bufferable (reflecting inner cacheability rules) +* +* \param OuterCp Configures the outer cache policy. +* \param InnerCp Configures the inner cache policy. +* \param IsShareable Configures the memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) + +/** +* MPU Memory Access Attribute non-cacheable policy. +*/ +#define ARM_MPU_CACHEP_NOCACHE 0U + +/** +* MPU Memory Access Attribute write-back, write and read allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_WRA 1U + +/** +* MPU Memory Access Attribute write-through, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WT_NWA 2U + +/** +* MPU Memory Access Attribute write-back, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_NWA 3U + + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; //!< The region base address register value (RBAR) + uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DSB(); + __ISB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DSB(); + __ISB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + MPU->RNR = rnr; + MPU->RASR = 0U; +} + +/** Configure an MPU region. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) +{ + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) +{ + MPU->RNR = rnr; + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + while (cnt > MPU_TYPE_RALIASES) { + orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); + table += MPU_TYPE_RALIASES; + cnt -= MPU_TYPE_RALIASES; + } + orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); +} + +#endif diff --git a/Drivers/CMSIS/Include/mpu_armv8.h b/Drivers/CMSIS/Include/mpu_armv8.h index 62571da..99ee9f9 100644 --- a/Drivers/CMSIS/Include/mpu_armv8.h +++ b/Drivers/CMSIS/Include/mpu_armv8.h @@ -1,333 +1,333 @@ -/****************************************************************************** - * @file mpu_armv8.h - * @brief CMSIS MPU API for Armv8-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV8_H -#define ARM_MPU_ARMV8_H - -/** \brief Attribute for device memory (outer only) */ -#define ARM_MPU_ATTR_DEVICE ( 0U ) - -/** \brief Attribute for non-cacheable, normal memory */ -#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) - -/** \brief Attribute for normal memory (outer and inner) -* \param NT Non-Transient: Set to 1 for non-transient data. -* \param WB Write-Back: Set to 1 to use write-back update policy. -* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. -* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. -*/ -#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ - (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) - -/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) - -/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) - -/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGRE (2U) - -/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_GRE (3U) - -/** \brief Memory Attribute -* \param O Outer memory attributes -* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes -*/ -#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) - -/** \brief Normal memory non-shareable */ -#define ARM_MPU_SH_NON (0U) - -/** \brief Normal memory outer shareable */ -#define ARM_MPU_SH_OUTER (2U) - -/** \brief Normal memory inner shareable */ -#define ARM_MPU_SH_INNER (3U) - -/** \brief Memory access permissions -* \param RO Read-Only: Set to 1 for read-only memory. -* \param NP Non-Privileged: Set to 1 for non-privileged memory. -*/ -#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) - -/** \brief Region Base Address Register value -* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. -* \param SH Defines the Shareability domain for this memory region. -* \param RO Read-Only: Set to 1 for a read-only memory region. -* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. -* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. -*/ -#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ - ((BASE & MPU_RBAR_BASE_Msk) | \ - ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ - ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ - ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) - -/** \brief Region Limit Address Register value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR(LIMIT, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; /*!< Region Base Address Register value */ - uint32_t RLAR; /*!< Region Limit Address Register value */ -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -#ifdef MPU_NS -/** Enable the Non-secure MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the Non-secure MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable_NS(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} -#endif - -/** Set the memory attribute encoding to the given MPU. -* \param mpu Pointer to the MPU to be configured. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) -{ - const uint8_t reg = idx / 4U; - const uint32_t pos = ((idx % 4U) * 8U); - const uint32_t mask = 0xFFU << pos; - - if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { - return; // invalid index - } - - mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); -} - -/** Set the memory attribute encoding. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU, idx, attr); -} - -#ifdef MPU_NS -/** Set the memory attribute encoding to the Non-secure MPU. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); -} -#endif - -/** Clear and disable the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) -{ - mpu->RNR = rnr; - mpu->RLAR = 0U; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU, rnr); -} - -#ifdef MPU_NS -/** Clear and disable the given Non-secure MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU_NS, rnr); -} -#endif - -/** Configure the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - mpu->RNR = rnr; - mpu->RBAR = rbar; - mpu->RLAR = rlar; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); -} - -#ifdef MPU_NS -/** Configure the given Non-secure MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); -} -#endif - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table to the given MPU. -* \param mpu Pointer to the MPU registers to be used. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - if (cnt == 1U) { - mpu->RNR = rnr; - orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); - } else { - uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); - uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; - - mpu->RNR = rnrBase; - while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { - uint32_t c = MPU_TYPE_RALIASES - rnrOffset; - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); - table += c; - cnt -= c; - rnrOffset = 0U; - rnrBase += MPU_TYPE_RALIASES; - mpu->RNR = rnrBase; - } - - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); - } -} - -/** Load the given number of MPU regions from a table. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU, rnr, table, cnt); -} - -#ifdef MPU_NS -/** Load the given number of MPU regions from a table to the Non-secure MPU. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); -} -#endif - -#endif - +/****************************************************************************** + * @file mpu_armv8.h + * @brief CMSIS MPU API for Armv8-M MPU + * @version V5.0.4 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2017-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV8_H +#define ARM_MPU_ARMV8_H + +/** \brief Attribute for device memory (outer only) */ +#define ARM_MPU_ATTR_DEVICE ( 0U ) + +/** \brief Attribute for non-cacheable, normal memory */ +#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) + +/** \brief Attribute for normal memory (outer and inner) +* \param NT Non-Transient: Set to 1 for non-transient data. +* \param WB Write-Back: Set to 1 to use write-back update policy. +* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. +* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. +*/ +#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ + (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) + +/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) + +/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) + +/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGRE (2U) + +/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_GRE (3U) + +/** \brief Memory Attribute +* \param O Outer memory attributes +* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes +*/ +#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) + +/** \brief Normal memory non-shareable */ +#define ARM_MPU_SH_NON (0U) + +/** \brief Normal memory outer shareable */ +#define ARM_MPU_SH_OUTER (2U) + +/** \brief Normal memory inner shareable */ +#define ARM_MPU_SH_INNER (3U) + +/** \brief Memory access permissions +* \param RO Read-Only: Set to 1 for read-only memory. +* \param NP Non-Privileged: Set to 1 for non-privileged memory. +*/ +#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) + +/** \brief Region Base Address Register value +* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. +* \param SH Defines the Shareability domain for this memory region. +* \param RO Read-Only: Set to 1 for a read-only memory region. +* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. +* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. +*/ +#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ + ((BASE & MPU_RBAR_BASE_Msk) | \ + ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ + ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ + ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) + +/** \brief Region Limit Address Register value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR(LIMIT, IDX) \ + ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ + ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; /*!< Region Base Address Register value */ + uint32_t RLAR; /*!< Region Limit Address Register value */ +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DSB(); + __ISB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DSB(); + __ISB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; +} + +#ifdef MPU_NS +/** Enable the Non-secure MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) +{ + __DSB(); + __ISB(); + MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif +} + +/** Disable the Non-secure MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable_NS(void) +{ + __DSB(); + __ISB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; +} +#endif + +/** Set the memory attribute encoding to the given MPU. +* \param mpu Pointer to the MPU to be configured. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) +{ + const uint8_t reg = idx / 4U; + const uint32_t pos = ((idx % 4U) * 8U); + const uint32_t mask = 0xFFU << pos; + + if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { + return; // invalid index + } + + mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); +} + +/** Set the memory attribute encoding. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU, idx, attr); +} + +#ifdef MPU_NS +/** Set the memory attribute encoding to the Non-secure MPU. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); +} +#endif + +/** Clear and disable the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) +{ + mpu->RNR = rnr; + mpu->RLAR = 0U; +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU, rnr); +} + +#ifdef MPU_NS +/** Clear and disable the given Non-secure MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU_NS, rnr); +} +#endif + +/** Configure the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + mpu->RNR = rnr; + mpu->RBAR = rbar; + mpu->RLAR = rlar; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); +} + +#ifdef MPU_NS +/** Configure the given Non-secure MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); +} +#endif + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table to the given MPU. +* \param mpu Pointer to the MPU registers to be used. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + if (cnt == 1U) { + mpu->RNR = rnr; + orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); + } else { + uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); + uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; + + mpu->RNR = rnrBase; + while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { + uint32_t c = MPU_TYPE_RALIASES - rnrOffset; + orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); + table += c; + cnt -= c; + rnrOffset = 0U; + rnrBase += MPU_TYPE_RALIASES; + mpu->RNR = rnrBase; + } + + orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); + } +} + +/** Load the given number of MPU regions from a table. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU, rnr, table, cnt); +} + +#ifdef MPU_NS +/** Load the given number of MPU regions from a table to the Non-secure MPU. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); +} +#endif + +#endif + diff --git a/Drivers/CMSIS/Include/tz_context.h b/Drivers/CMSIS/Include/tz_context.h index 0d09749..d4c1474 100644 --- a/Drivers/CMSIS/Include/tz_context.h +++ b/Drivers/CMSIS/Include/tz_context.h @@ -1,70 +1,70 @@ -/****************************************************************************** - * @file tz_context.h - * @brief Context Management for Armv8-M TrustZone - * @version V1.0.1 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed 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 - * - * 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. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef TZ_CONTEXT_H -#define TZ_CONTEXT_H - -#include - -#ifndef TZ_MODULEID_T -#define TZ_MODULEID_T -/// \details Data type that identifies secure software modules called by a process. -typedef uint32_t TZ_ModuleId_t; -#endif - -/// \details TZ Memory ID identifies an allocated memory slot. -typedef uint32_t TZ_MemoryId_t; - -/// Initialize secure context memory system -/// \return execution status (1: success, 0: error) -uint32_t TZ_InitContextSystem_S (void); - -/// Allocate context memory for calling secure software modules in TrustZone -/// \param[in] module identifies software modules called from non-secure mode -/// \return value != 0 id TrustZone memory slot identifier -/// \return value 0 no memory available or internal error -TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module); - -/// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id); - -/// Load secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_LoadContext_S (TZ_MemoryId_t id); - -/// Store secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_StoreContext_S (TZ_MemoryId_t id); - -#endif // TZ_CONTEXT_H +/****************************************************************************** + * @file tz_context.h + * @brief Context Management for Armv8-M TrustZone + * @version V1.0.1 + * @date 10. January 2018 + ******************************************************************************/ +/* + * Copyright (c) 2017-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef TZ_CONTEXT_H +#define TZ_CONTEXT_H + +#include + +#ifndef TZ_MODULEID_T +#define TZ_MODULEID_T +/// \details Data type that identifies secure software modules called by a process. +typedef uint32_t TZ_ModuleId_t; +#endif + +/// \details TZ Memory ID identifies an allocated memory slot. +typedef uint32_t TZ_MemoryId_t; + +/// Initialize secure context memory system +/// \return execution status (1: success, 0: error) +uint32_t TZ_InitContextSystem_S (void); + +/// Allocate context memory for calling secure software modules in TrustZone +/// \param[in] module identifies software modules called from non-secure mode +/// \return value != 0 id TrustZone memory slot identifier +/// \return value 0 no memory available or internal error +TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module); + +/// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S +/// \param[in] id TrustZone memory slot identifier +/// \return execution status (1: success, 0: error) +uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id); + +/// Load secure context (called on RTOS thread context switch) +/// \param[in] id TrustZone memory slot identifier +/// \return execution status (1: success, 0: error) +uint32_t TZ_LoadContext_S (TZ_MemoryId_t id); + +/// Store secure context (called on RTOS thread context switch) +/// \param[in] id TrustZone memory slot identifier +/// \return execution status (1: success, 0: error) +uint32_t TZ_StoreContext_S (TZ_MemoryId_t id); + +#endif // TZ_CONTEXT_H diff --git a/Drivers/CMSIS/LICENSE.txt b/Drivers/CMSIS/LICENSE.txt index 8dada3e..c0ee812 100644 --- a/Drivers/CMSIS/LICENSE.txt +++ b/Drivers/CMSIS/LICENSE.txt @@ -1,201 +1,201 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "{}" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright {yyyy} {name of copyright owner} - - Licensed 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. + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "{}" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright {yyyy} {name of copyright owner} + + Licensed 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. diff --git a/Drivers/Embedded-Base b/Drivers/Embedded-Base index 18bfb4f..ff34106 160000 --- a/Drivers/Embedded-Base +++ b/Drivers/Embedded-Base @@ -1 +1 @@ -Subproject commit 18bfb4f15d491ac53a69bcdc2a297b70a7d0639b +Subproject commit ff34106b18e296434fc817d7a9c66efc28c07abe diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h b/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h index 934f1f9..17b5cee 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h @@ -1,4014 +1,4014 @@ -/** - ****************************************************************************** - * @file stm32_hal_legacy.h - * @author MCD Application Team - * @brief This file contains aliases definition for the STM32Cube HAL constants - * macros and functions maintained for legacy purpose. - ****************************************************************************** - * @attention - * - * Copyright (c) 2021 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32_HAL_LEGACY -#define STM32_HAL_LEGACY - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Defines HAL CRYP Aliased Defines maintained for legacy purpose - * @{ - */ -#define AES_FLAG_RDERR CRYP_FLAG_RDERR -#define AES_FLAG_WRERR CRYP_FLAG_WRERR -#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF -#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR -#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR -#if defined(STM32U5) || defined(STM32H7) || defined(STM32MP1) -#define CRYP_DATATYPE_32B CRYP_NO_SWAP -#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP -#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP -#define CRYP_DATATYPE_1B CRYP_BIT_SWAP -#if defined(STM32U5) -#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF -#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF -#endif /* STM32U5 */ -#endif /* STM32U5 || STM32H7 || STM32MP1 */ -/** - * @} - */ - -/** @defgroup HAL_ADC_Aliased_Defines HAL ADC Aliased Defines maintained for legacy purpose - * @{ - */ -#define ADC_RESOLUTION12b ADC_RESOLUTION_12B -#define ADC_RESOLUTION10b ADC_RESOLUTION_10B -#define ADC_RESOLUTION8b ADC_RESOLUTION_8B -#define ADC_RESOLUTION6b ADC_RESOLUTION_6B -#define OVR_DATA_OVERWRITTEN ADC_OVR_DATA_OVERWRITTEN -#define OVR_DATA_PRESERVED ADC_OVR_DATA_PRESERVED -#define EOC_SINGLE_CONV ADC_EOC_SINGLE_CONV -#define EOC_SEQ_CONV ADC_EOC_SEQ_CONV -#define EOC_SINGLE_SEQ_CONV ADC_EOC_SINGLE_SEQ_CONV -#define REGULAR_GROUP ADC_REGULAR_GROUP -#define INJECTED_GROUP ADC_INJECTED_GROUP -#define REGULAR_INJECTED_GROUP ADC_REGULAR_INJECTED_GROUP -#define AWD_EVENT ADC_AWD_EVENT -#define AWD1_EVENT ADC_AWD1_EVENT -#define AWD2_EVENT ADC_AWD2_EVENT -#define AWD3_EVENT ADC_AWD3_EVENT -#define OVR_EVENT ADC_OVR_EVENT -#define JQOVF_EVENT ADC_JQOVF_EVENT -#define ALL_CHANNELS ADC_ALL_CHANNELS -#define REGULAR_CHANNELS ADC_REGULAR_CHANNELS -#define INJECTED_CHANNELS ADC_INJECTED_CHANNELS -#define SYSCFG_FLAG_SENSOR_ADC ADC_FLAG_SENSOR -#define SYSCFG_FLAG_VREF_ADC ADC_FLAG_VREFINT -#define ADC_CLOCKPRESCALER_PCLK_DIV1 ADC_CLOCK_SYNC_PCLK_DIV1 -#define ADC_CLOCKPRESCALER_PCLK_DIV2 ADC_CLOCK_SYNC_PCLK_DIV2 -#define ADC_CLOCKPRESCALER_PCLK_DIV4 ADC_CLOCK_SYNC_PCLK_DIV4 -#define ADC_CLOCKPRESCALER_PCLK_DIV6 ADC_CLOCK_SYNC_PCLK_DIV6 -#define ADC_CLOCKPRESCALER_PCLK_DIV8 ADC_CLOCK_SYNC_PCLK_DIV8 -#define ADC_EXTERNALTRIG0_T6_TRGO ADC_EXTERNALTRIGCONV_T6_TRGO -#define ADC_EXTERNALTRIG1_T21_CC2 ADC_EXTERNALTRIGCONV_T21_CC2 -#define ADC_EXTERNALTRIG2_T2_TRGO ADC_EXTERNALTRIGCONV_T2_TRGO -#define ADC_EXTERNALTRIG3_T2_CC4 ADC_EXTERNALTRIGCONV_T2_CC4 -#define ADC_EXTERNALTRIG4_T22_TRGO ADC_EXTERNALTRIGCONV_T22_TRGO -#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_EXTERNALTRIGCONV_EXT_IT11 -#define ADC_CLOCK_ASYNC ADC_CLOCK_ASYNC_DIV1 -#define ADC_EXTERNALTRIG_EDGE_NONE ADC_EXTERNALTRIGCONVEDGE_NONE -#define ADC_EXTERNALTRIG_EDGE_RISING ADC_EXTERNALTRIGCONVEDGE_RISING -#define ADC_EXTERNALTRIG_EDGE_FALLING ADC_EXTERNALTRIGCONVEDGE_FALLING -#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING -#define ADC_SAMPLETIME_2CYCLE_5 ADC_SAMPLETIME_2CYCLES_5 - -#define HAL_ADC_STATE_BUSY_REG HAL_ADC_STATE_REG_BUSY -#define HAL_ADC_STATE_BUSY_INJ HAL_ADC_STATE_INJ_BUSY -#define HAL_ADC_STATE_EOC_REG HAL_ADC_STATE_REG_EOC -#define HAL_ADC_STATE_EOC_INJ HAL_ADC_STATE_INJ_EOC -#define HAL_ADC_STATE_ERROR HAL_ADC_STATE_ERROR_INTERNAL -#define HAL_ADC_STATE_BUSY HAL_ADC_STATE_BUSY_INTERNAL -#define HAL_ADC_STATE_AWD HAL_ADC_STATE_AWD1 - -#if defined(STM32H7) -#define ADC_CHANNEL_VBAT_DIV4 ADC_CHANNEL_VBAT -#endif /* STM32H7 */ - -#if defined(STM32U5) -#define ADC_SAMPLETIME_5CYCLE ADC_SAMPLETIME_5CYCLES -#define ADC_SAMPLETIME_391CYCLES_5 ADC_SAMPLETIME_391CYCLES -#define ADC4_SAMPLETIME_160CYCLES_5 ADC4_SAMPLETIME_814CYCLES_5 -#endif /* STM32U5 */ - -/** - * @} - */ - -/** @defgroup HAL_CEC_Aliased_Defines HAL CEC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define __HAL_CEC_GET_IT __HAL_CEC_GET_FLAG - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Defines HAL COMP Aliased Defines maintained for legacy purpose - * @{ - */ -#define COMP_WINDOWMODE_DISABLED COMP_WINDOWMODE_DISABLE -#define COMP_WINDOWMODE_ENABLED COMP_WINDOWMODE_ENABLE -#define COMP_EXTI_LINE_COMP1_EVENT COMP_EXTI_LINE_COMP1 -#define COMP_EXTI_LINE_COMP2_EVENT COMP_EXTI_LINE_COMP2 -#define COMP_EXTI_LINE_COMP3_EVENT COMP_EXTI_LINE_COMP3 -#define COMP_EXTI_LINE_COMP4_EVENT COMP_EXTI_LINE_COMP4 -#define COMP_EXTI_LINE_COMP5_EVENT COMP_EXTI_LINE_COMP5 -#define COMP_EXTI_LINE_COMP6_EVENT COMP_EXTI_LINE_COMP6 -#define COMP_EXTI_LINE_COMP7_EVENT COMP_EXTI_LINE_COMP7 -#if defined(STM32L0) -#define COMP_LPTIMCONNECTION_ENABLED ((uint32_t)0x00000003U) /*!< COMPX output generic naming: connected to LPTIM input 1 for COMP1, LPTIM input 2 for COMP2 */ -#endif -#define COMP_OUTPUT_COMP6TIM2OCREFCLR COMP_OUTPUT_COMP6_TIM2OCREFCLR -#if defined(STM32F373xC) || defined(STM32F378xx) -#define COMP_OUTPUT_TIM3IC1 COMP_OUTPUT_COMP1_TIM3IC1 -#define COMP_OUTPUT_TIM3OCREFCLR COMP_OUTPUT_COMP1_TIM3OCREFCLR -#endif /* STM32F373xC || STM32F378xx */ - -#if defined(STM32L0) || defined(STM32L4) -#define COMP_WINDOWMODE_ENABLE COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON - -#define COMP_NONINVERTINGINPUT_IO1 COMP_INPUT_PLUS_IO1 -#define COMP_NONINVERTINGINPUT_IO2 COMP_INPUT_PLUS_IO2 -#define COMP_NONINVERTINGINPUT_IO3 COMP_INPUT_PLUS_IO3 -#define COMP_NONINVERTINGINPUT_IO4 COMP_INPUT_PLUS_IO4 -#define COMP_NONINVERTINGINPUT_IO5 COMP_INPUT_PLUS_IO5 -#define COMP_NONINVERTINGINPUT_IO6 COMP_INPUT_PLUS_IO6 - -#define COMP_INVERTINGINPUT_1_4VREFINT COMP_INPUT_MINUS_1_4VREFINT -#define COMP_INVERTINGINPUT_1_2VREFINT COMP_INPUT_MINUS_1_2VREFINT -#define COMP_INVERTINGINPUT_3_4VREFINT COMP_INPUT_MINUS_3_4VREFINT -#define COMP_INVERTINGINPUT_VREFINT COMP_INPUT_MINUS_VREFINT -#define COMP_INVERTINGINPUT_DAC1_CH1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC1_CH2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_DAC1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO1 COMP_INPUT_MINUS_IO1 -#if defined(STM32L0) -/* Issue fixed on STM32L0 COMP driver: only 2 dedicated IO (IO1 and IO2), */ -/* IO2 was wrongly assigned to IO shared with DAC and IO3 was corresponding */ -/* to the second dedicated IO (only for COMP2). */ -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO2 -#else -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_IO2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO3 -#endif -#define COMP_INVERTINGINPUT_IO4 COMP_INPUT_MINUS_IO4 -#define COMP_INVERTINGINPUT_IO5 COMP_INPUT_MINUS_IO5 - -#define COMP_OUTPUTLEVEL_LOW COMP_OUTPUT_LEVEL_LOW -#define COMP_OUTPUTLEVEL_HIGH COMP_OUTPUT_LEVEL_HIGH - -/* Note: Literal "COMP_FLAG_LOCK" kept for legacy purpose. */ -/* To check COMP lock state, use macro "__HAL_COMP_IS_LOCKED()". */ -#if defined(COMP_CSR_LOCK) -#define COMP_FLAG_LOCK COMP_CSR_LOCK -#elif defined(COMP_CSR_COMP1LOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMP1LOCK -#elif defined(COMP_CSR_COMPxLOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMPxLOCK -#endif - -#if defined(STM32L4) -#define COMP_BLANKINGSRCE_TIM1OC5 COMP_BLANKINGSRC_TIM1_OC5_COMP1 -#define COMP_BLANKINGSRCE_TIM2OC3 COMP_BLANKINGSRC_TIM2_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC3 COMP_BLANKINGSRC_TIM3_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC4 COMP_BLANKINGSRC_TIM3_OC4_COMP2 -#define COMP_BLANKINGSRCE_TIM8OC5 COMP_BLANKINGSRC_TIM8_OC5_COMP2 -#define COMP_BLANKINGSRCE_TIM15OC1 COMP_BLANKINGSRC_TIM15_OC1_COMP2 -#define COMP_BLANKINGSRCE_NONE COMP_BLANKINGSRC_NONE -#endif - -#if defined(STM32L0) -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWSPEED COMP_POWERMODE_ULTRALOWPOWER -#else -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_HIGHSPEED -#define COMP_MODE_MEDIUMSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWPOWER COMP_POWERMODE_LOWPOWER -#define COMP_MODE_ULTRALOWPOWER COMP_POWERMODE_ULTRALOWPOWER -#endif - -#endif -/** - * @} - */ - -/** @defgroup HAL_CORTEX_Aliased_Defines HAL CORTEX Aliased Defines maintained for legacy purpose - * @{ - */ -#define __HAL_CORTEX_SYSTICKCLK_CONFIG HAL_SYSTICK_CLKSourceConfig -#if defined(STM32U5) -#define MPU_DEVICE_nGnRnE MPU_DEVICE_NGNRNE -#define MPU_DEVICE_nGnRE MPU_DEVICE_NGNRE -#define MPU_DEVICE_nGRE MPU_DEVICE_NGRE -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup CRC_Aliases CRC API aliases - * @{ - */ -#if defined(STM32C0) -#else -#define HAL_CRC_Input_Data_Reverse HAL_CRCEx_Input_Data_Reverse /*!< Aliased to HAL_CRCEx_Input_Data_Reverse for inter STM32 series compatibility */ -#define HAL_CRC_Output_Data_Reverse HAL_CRCEx_Output_Data_Reverse /*!< Aliased to HAL_CRCEx_Output_Data_Reverse for inter STM32 series compatibility */ -#endif -/** - * @} - */ - -/** @defgroup HAL_CRC_Aliased_Defines HAL CRC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define CRC_OUTPUTDATA_INVERSION_DISABLED CRC_OUTPUTDATA_INVERSION_DISABLE -#define CRC_OUTPUTDATA_INVERSION_ENABLED CRC_OUTPUTDATA_INVERSION_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Defines HAL DAC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define DAC1_CHANNEL_1 DAC_CHANNEL_1 -#define DAC1_CHANNEL_2 DAC_CHANNEL_2 -#define DAC2_CHANNEL_1 DAC_CHANNEL_1 -#define DAC_WAVE_NONE 0x00000000U -#define DAC_WAVE_NOISE DAC_CR_WAVE1_0 -#define DAC_WAVE_TRIANGLE DAC_CR_WAVE1_1 -#define DAC_WAVEGENERATION_NONE DAC_WAVE_NONE -#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE -#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE - -#if defined(STM32G4) || defined(STM32H7) || defined (STM32U5) -#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL -#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL -#endif - -#if defined(STM32U5) -#define DAC_TRIGGER_STOP_LPTIM1_OUT DAC_TRIGGER_STOP_LPTIM1_CH1 -#define DAC_TRIGGER_STOP_LPTIM3_OUT DAC_TRIGGER_STOP_LPTIM3_CH1 -#define DAC_TRIGGER_LPTIM1_OUT DAC_TRIGGER_LPTIM1_CH1 -#define DAC_TRIGGER_LPTIM3_OUT DAC_TRIGGER_LPTIM3_CH1 -#endif - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32G0) || defined(STM32L5) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) -#define HAL_DAC_MSP_INIT_CB_ID HAL_DAC_MSPINIT_CB_ID -#define HAL_DAC_MSP_DEINIT_CB_ID HAL_DAC_MSPDEINIT_CB_ID -#endif - -/** - * @} - */ - -/** @defgroup HAL_DMA_Aliased_Defines HAL DMA Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_REMAPDMA_ADC_DMA_CH2 DMA_REMAP_ADC_DMA_CH2 -#define HAL_REMAPDMA_USART1_TX_DMA_CH4 DMA_REMAP_USART1_TX_DMA_CH4 -#define HAL_REMAPDMA_USART1_RX_DMA_CH5 DMA_REMAP_USART1_RX_DMA_CH5 -#define HAL_REMAPDMA_TIM16_DMA_CH4 DMA_REMAP_TIM16_DMA_CH4 -#define HAL_REMAPDMA_TIM17_DMA_CH2 DMA_REMAP_TIM17_DMA_CH2 -#define HAL_REMAPDMA_USART3_DMA_CH32 DMA_REMAP_USART3_DMA_CH32 -#define HAL_REMAPDMA_TIM16_DMA_CH6 DMA_REMAP_TIM16_DMA_CH6 -#define HAL_REMAPDMA_TIM17_DMA_CH7 DMA_REMAP_TIM17_DMA_CH7 -#define HAL_REMAPDMA_SPI2_DMA_CH67 DMA_REMAP_SPI2_DMA_CH67 -#define HAL_REMAPDMA_USART2_DMA_CH67 DMA_REMAP_USART2_DMA_CH67 -#define HAL_REMAPDMA_I2C1_DMA_CH76 DMA_REMAP_I2C1_DMA_CH76 -#define HAL_REMAPDMA_TIM1_DMA_CH6 DMA_REMAP_TIM1_DMA_CH6 -#define HAL_REMAPDMA_TIM2_DMA_CH7 DMA_REMAP_TIM2_DMA_CH7 -#define HAL_REMAPDMA_TIM3_DMA_CH6 DMA_REMAP_TIM3_DMA_CH6 - -#define IS_HAL_REMAPDMA IS_DMA_REMAP -#define __HAL_REMAPDMA_CHANNEL_ENABLE __HAL_DMA_REMAP_CHANNEL_ENABLE -#define __HAL_REMAPDMA_CHANNEL_DISABLE __HAL_DMA_REMAP_CHANNEL_DISABLE - -#if defined(STM32L4) - -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI1 HAL_DMAMUX1_REQ_GEN_EXTI1 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI2 HAL_DMAMUX1_REQ_GEN_EXTI2 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI3 HAL_DMAMUX1_REQ_GEN_EXTI3 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI4 HAL_DMAMUX1_REQ_GEN_EXTI4 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI5 HAL_DMAMUX1_REQ_GEN_EXTI5 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI6 HAL_DMAMUX1_REQ_GEN_EXTI6 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI7 HAL_DMAMUX1_REQ_GEN_EXTI7 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI8 HAL_DMAMUX1_REQ_GEN_EXTI8 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI9 HAL_DMAMUX1_REQ_GEN_EXTI9 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI10 HAL_DMAMUX1_REQ_GEN_EXTI10 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI11 HAL_DMAMUX1_REQ_GEN_EXTI11 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI12 HAL_DMAMUX1_REQ_GEN_EXTI12 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI13 HAL_DMAMUX1_REQ_GEN_EXTI13 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI14 HAL_DMAMUX1_REQ_GEN_EXTI14 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI15 HAL_DMAMUX1_REQ_GEN_EXTI15 -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH3_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH3_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_DSI_TE HAL_DMAMUX1_REQ_GEN_DSI_TE -#define HAL_DMAMUX1_REQUEST_GEN_DSI_EOT HAL_DMAMUX1_REQ_GEN_DSI_EOT -#define HAL_DMAMUX1_REQUEST_GEN_DMA2D_EOT HAL_DMAMUX1_REQ_GEN_DMA2D_EOT -#define HAL_DMAMUX1_REQUEST_GEN_LTDC_IT HAL_DMAMUX1_REQ_GEN_LTDC_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#if defined(STM32L4R5xx) || defined(STM32L4R9xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx) -#define DMA_REQUEST_DCMI_PSSI DMA_REQUEST_DCMI -#endif - -#endif /* STM32L4 */ - -#if defined(STM32G0) -#define DMA_REQUEST_DAC1_CHANNEL1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC1_CHANNEL2 DMA_REQUEST_DAC1_CH2 -#define DMA_REQUEST_TIM16_TRIG_COM DMA_REQUEST_TIM16_COM -#define DMA_REQUEST_TIM17_TRIG_COM DMA_REQUEST_TIM17_COM - -#define LL_DMAMUX_REQ_TIM16_TRIG_COM LL_DMAMUX_REQ_TIM16_COM -#define LL_DMAMUX_REQ_TIM17_TRIG_COM LL_DMAMUX_REQ_TIM17_COM -#endif - -#if defined(STM32H7) - -#define DMA_REQUEST_DAC1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC2 DMA_REQUEST_DAC1_CH2 - -#define BDMA_REQUEST_LP_UART1_RX BDMA_REQUEST_LPUART1_RX -#define BDMA_REQUEST_LP_UART1_TX BDMA_REQUEST_LPUART1_TX - -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX1_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_TIM12_TRGO HAL_DMAMUX1_REQ_GEN_TIM12_TRGO - -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH0_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH0_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH1_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH1_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH2_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH2_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH3_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH3_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH4_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH4_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH5_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH5_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH6_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH6_EVT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_RX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_TX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM2_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX2_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM3_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX2_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM4_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM5_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM5_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_WKUP HAL_DMAMUX2_REQ_GEN_I2C4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_WKUP HAL_DMAMUX2_REQ_GEN_SPI6_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_COMP1_OUT HAL_DMAMUX2_REQ_GEN_COMP1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_COMP2_OUT HAL_DMAMUX2_REQ_GEN_COMP2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_RTC_WKUP HAL_DMAMUX2_REQ_GEN_RTC_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_EXTI0 HAL_DMAMUX2_REQ_GEN_EXTI0 -#define HAL_DMAMUX2_REQUEST_GEN_EXTI2 HAL_DMAMUX2_REQ_GEN_EXTI2 -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_IT_EVT HAL_DMAMUX2_REQ_GEN_I2C4_IT_EVT -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_IT HAL_DMAMUX2_REQ_GEN_SPI6_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_TX_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_RX_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_IT HAL_DMAMUX2_REQ_GEN_ADC3_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_AWD1_OUT HAL_DMAMUX2_REQ_GEN_ADC3_AWD1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH0_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH0_IT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH1_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH1_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#define DFSDM_FILTER_EXT_TRIG_LPTIM1 DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM2 DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM3 DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT - -#define DAC_TRIGGER_LP1_OUT DAC_TRIGGER_LPTIM1_OUT -#define DAC_TRIGGER_LP2_OUT DAC_TRIGGER_LPTIM2_OUT - -#endif /* STM32H7 */ - -#if defined(STM32U5) -#define GPDMA1_REQUEST_DCMI GPDMA1_REQUEST_DCMI_PSSI -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Defines HAL FLASH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define TYPEPROGRAM_BYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_HALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_WORD FLASH_TYPEPROGRAM_WORD -#define TYPEPROGRAM_DOUBLEWORD FLASH_TYPEPROGRAM_DOUBLEWORD -#define TYPEERASE_SECTORS FLASH_TYPEERASE_SECTORS -#define TYPEERASE_PAGES FLASH_TYPEERASE_PAGES -#define TYPEERASE_PAGEERASE FLASH_TYPEERASE_PAGES -#define TYPEERASE_MASSERASE FLASH_TYPEERASE_MASSERASE -#define WRPSTATE_DISABLE OB_WRPSTATE_DISABLE -#define WRPSTATE_ENABLE OB_WRPSTATE_ENABLE -#define HAL_FLASH_TIMEOUT_VALUE FLASH_TIMEOUT_VALUE -#define OBEX_PCROP OPTIONBYTE_PCROP -#define OBEX_BOOTCONFIG OPTIONBYTE_BOOTCONFIG -#define PCROPSTATE_DISABLE OB_PCROP_STATE_DISABLE -#define PCROPSTATE_ENABLE OB_PCROP_STATE_ENABLE -#define TYPEERASEDATA_BYTE FLASH_TYPEERASEDATA_BYTE -#define TYPEERASEDATA_HALFWORD FLASH_TYPEERASEDATA_HALFWORD -#define TYPEERASEDATA_WORD FLASH_TYPEERASEDATA_WORD -#define TYPEPROGRAMDATA_BYTE FLASH_TYPEPROGRAMDATA_BYTE -#define TYPEPROGRAMDATA_HALFWORD FLASH_TYPEPROGRAMDATA_HALFWORD -#define TYPEPROGRAMDATA_WORD FLASH_TYPEPROGRAMDATA_WORD -#define TYPEPROGRAMDATA_FASTBYTE FLASH_TYPEPROGRAMDATA_FASTBYTE -#define TYPEPROGRAMDATA_FASTHALFWORD FLASH_TYPEPROGRAMDATA_FASTHALFWORD -#define TYPEPROGRAMDATA_FASTWORD FLASH_TYPEPROGRAMDATA_FASTWORD -#define PAGESIZE FLASH_PAGE_SIZE -#define TYPEPROGRAM_FASTBYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_FASTHALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_FASTWORD FLASH_TYPEPROGRAM_WORD -#define VOLTAGE_RANGE_1 FLASH_VOLTAGE_RANGE_1 -#define VOLTAGE_RANGE_2 FLASH_VOLTAGE_RANGE_2 -#define VOLTAGE_RANGE_3 FLASH_VOLTAGE_RANGE_3 -#define VOLTAGE_RANGE_4 FLASH_VOLTAGE_RANGE_4 -#define TYPEPROGRAM_FAST FLASH_TYPEPROGRAM_FAST -#define TYPEPROGRAM_FAST_AND_LAST FLASH_TYPEPROGRAM_FAST_AND_LAST -#define WRPAREA_BANK1_AREAA OB_WRPAREA_BANK1_AREAA -#define WRPAREA_BANK1_AREAB OB_WRPAREA_BANK1_AREAB -#define WRPAREA_BANK2_AREAA OB_WRPAREA_BANK2_AREAA -#define WRPAREA_BANK2_AREAB OB_WRPAREA_BANK2_AREAB -#define IWDG_STDBY_FREEZE OB_IWDG_STDBY_FREEZE -#define IWDG_STDBY_ACTIVE OB_IWDG_STDBY_RUN -#define IWDG_STOP_FREEZE OB_IWDG_STOP_FREEZE -#define IWDG_STOP_ACTIVE OB_IWDG_STOP_RUN -#define FLASH_ERROR_NONE HAL_FLASH_ERROR_NONE -#define FLASH_ERROR_RD HAL_FLASH_ERROR_RD -#define FLASH_ERROR_PG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_PGP HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_WRP HAL_FLASH_ERROR_WRP -#define FLASH_ERROR_OPTV HAL_FLASH_ERROR_OPTV -#define FLASH_ERROR_OPTVUSR HAL_FLASH_ERROR_OPTVUSR -#define FLASH_ERROR_PROG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_OP HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_PGA HAL_FLASH_ERROR_PGA -#define FLASH_ERROR_SIZE HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_SIZ HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_PGS HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_MIS HAL_FLASH_ERROR_MIS -#define FLASH_ERROR_FAST HAL_FLASH_ERROR_FAST -#define FLASH_ERROR_FWWERR HAL_FLASH_ERROR_FWWERR -#define FLASH_ERROR_NOTZERO HAL_FLASH_ERROR_NOTZERO -#define FLASH_ERROR_OPERATION HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_ERS HAL_FLASH_ERROR_ERS -#define OB_WDG_SW OB_IWDG_SW -#define OB_WDG_HW OB_IWDG_HW -#define OB_SDADC12_VDD_MONITOR_SET OB_SDACD_VDD_MONITOR_SET -#define OB_SDADC12_VDD_MONITOR_RESET OB_SDACD_VDD_MONITOR_RESET -#define OB_RAM_PARITY_CHECK_SET OB_SRAM_PARITY_SET -#define OB_RAM_PARITY_CHECK_RESET OB_SRAM_PARITY_RESET -#define IS_OB_SDADC12_VDD_MONITOR IS_OB_SDACD_VDD_MONITOR -#define OB_RDP_LEVEL0 OB_RDP_LEVEL_0 -#define OB_RDP_LEVEL1 OB_RDP_LEVEL_1 -#define OB_RDP_LEVEL2 OB_RDP_LEVEL_2 -#if defined(STM32G0) || defined(STM32C0) -#define OB_BOOT_LOCK_DISABLE OB_BOOT_ENTRY_FORCED_NONE -#define OB_BOOT_LOCK_ENABLE OB_BOOT_ENTRY_FORCED_FLASH -#else -#define OB_BOOT_ENTRY_FORCED_NONE OB_BOOT_LOCK_DISABLE -#define OB_BOOT_ENTRY_FORCED_FLASH OB_BOOT_LOCK_ENABLE -#endif -#if defined(STM32H7) -#define FLASH_FLAG_SNECCE_BANK1RR FLASH_FLAG_SNECCERR_BANK1 -#define FLASH_FLAG_DBECCE_BANK1RR FLASH_FLAG_DBECCERR_BANK1 -#define FLASH_FLAG_STRBER_BANK1R FLASH_FLAG_STRBERR_BANK1 -#define FLASH_FLAG_SNECCE_BANK2RR FLASH_FLAG_SNECCERR_BANK2 -#define FLASH_FLAG_DBECCE_BANK2RR FLASH_FLAG_DBECCERR_BANK2 -#define FLASH_FLAG_STRBER_BANK2R FLASH_FLAG_STRBERR_BANK2 -#define FLASH_FLAG_WDW FLASH_FLAG_WBNE -#define OB_WRP_SECTOR_All OB_WRP_SECTOR_ALL -#endif /* STM32H7 */ -#if defined(STM32U5) -#define OB_USER_nRST_STOP OB_USER_NRST_STOP -#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY -#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW -#define OB_USER_nSWBOOT0 OB_USER_NSWBOOT0 -#define OB_USER_nBOOT0 OB_USER_NBOOT0 -#define OB_nBOOT0_RESET OB_NBOOT0_RESET -#define OB_nBOOT0_SET OB_NBOOT0_SET -#endif /* STM32U5 */ - -/** - * @} - */ - -/** @defgroup HAL_JPEG_Aliased_Macros HAL JPEG Aliased Macros maintained for legacy purpose - * @{ - */ - -#if defined(STM32H7) -#define __HAL_RCC_JPEG_CLK_ENABLE __HAL_RCC_JPGDECEN_CLK_ENABLE -#define __HAL_RCC_JPEG_CLK_DISABLE __HAL_RCC_JPGDECEN_CLK_DISABLE -#define __HAL_RCC_JPEG_FORCE_RESET __HAL_RCC_JPGDECRST_FORCE_RESET -#define __HAL_RCC_JPEG_RELEASE_RESET __HAL_RCC_JPGDECRST_RELEASE_RESET -#define __HAL_RCC_JPEG_CLK_SLEEP_ENABLE __HAL_RCC_JPGDEC_CLK_SLEEP_ENABLE -#define __HAL_RCC_JPEG_CLK_SLEEP_DISABLE __HAL_RCC_JPGDEC_CLK_SLEEP_DISABLE -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_SYSCFG_Aliased_Defines HAL SYSCFG Aliased Defines maintained for legacy purpose - * @{ - */ - -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA9 I2C_FASTMODEPLUS_PA9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA10 I2C_FASTMODEPLUS_PA10 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB6 I2C_FASTMODEPLUS_PB6 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB7 I2C_FASTMODEPLUS_PB7 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB8 I2C_FASTMODEPLUS_PB8 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB9 I2C_FASTMODEPLUS_PB9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C1 I2C_FASTMODEPLUS_I2C1 -#define HAL_SYSCFG_FASTMODEPLUS_I2C2 I2C_FASTMODEPLUS_I2C2 -#define HAL_SYSCFG_FASTMODEPLUS_I2C3 I2C_FASTMODEPLUS_I2C3 -#if defined(STM32G4) - -#define HAL_SYSCFG_EnableIOAnalogSwitchBooster HAL_SYSCFG_EnableIOSwitchBooster -#define HAL_SYSCFG_DisableIOAnalogSwitchBooster HAL_SYSCFG_DisableIOSwitchBooster -#define HAL_SYSCFG_EnableIOAnalogSwitchVDD HAL_SYSCFG_EnableIOSwitchVDD -#define HAL_SYSCFG_DisableIOAnalogSwitchVDD HAL_SYSCFG_DisableIOSwitchVDD -#endif /* STM32G4 */ - -/** - * @} - */ - - -/** @defgroup LL_FMC_Aliased_Defines LL FMC Aliased Defines maintained for compatibility purpose - * @{ - */ -#if defined(STM32L4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) -#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE FMC_NAND_WAIT_FEATURE_DISABLE -#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE FMC_NAND_WAIT_FEATURE_ENABLE -#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 FMC_NAND_MEM_BUS_WIDTH_8 -#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 FMC_NAND_MEM_BUS_WIDTH_16 -#elif defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) -#define FMC_NAND_WAIT_FEATURE_DISABLE FMC_NAND_PCC_WAIT_FEATURE_DISABLE -#define FMC_NAND_WAIT_FEATURE_ENABLE FMC_NAND_PCC_WAIT_FEATURE_ENABLE -#define FMC_NAND_MEM_BUS_WIDTH_8 FMC_NAND_PCC_MEM_BUS_WIDTH_8 -#define FMC_NAND_MEM_BUS_WIDTH_16 FMC_NAND_PCC_MEM_BUS_WIDTH_16 -#endif -/** - * @} - */ - -/** @defgroup LL_FSMC_Aliased_Defines LL FSMC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FSMC_NORSRAM_TYPEDEF FSMC_NORSRAM_TypeDef -#define FSMC_NORSRAM_EXTENDED_TYPEDEF FSMC_NORSRAM_EXTENDED_TypeDef -/** - * @} - */ - -/** @defgroup HAL_GPIO_Aliased_Macros HAL GPIO Aliased Macros maintained for legacy purpose - * @{ - */ -#define GET_GPIO_SOURCE GPIO_GET_INDEX -#define GET_GPIO_INDEX GPIO_GET_INDEX - -#if defined(STM32F4) -#define GPIO_AF12_SDMMC GPIO_AF12_SDIO -#define GPIO_AF12_SDMMC1 GPIO_AF12_SDIO -#endif - -#if defined(STM32F7) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32L4) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32H7) -#define GPIO_AF7_SDIO1 GPIO_AF7_SDMMC1 -#define GPIO_AF8_SDIO1 GPIO_AF8_SDMMC1 -#define GPIO_AF12_SDIO1 GPIO_AF12_SDMMC1 -#define GPIO_AF9_SDIO2 GPIO_AF9_SDMMC2 -#define GPIO_AF10_SDIO2 GPIO_AF10_SDMMC2 -#define GPIO_AF11_SDIO2 GPIO_AF11_SDMMC2 - -#if defined (STM32H743xx) || defined (STM32H753xx) || defined (STM32H750xx) || defined (STM32H742xx) || \ - defined (STM32H745xx) || defined (STM32H755xx) || defined (STM32H747xx) || defined (STM32H757xx) -#define GPIO_AF10_OTG2_HS GPIO_AF10_OTG2_FS -#define GPIO_AF10_OTG1_FS GPIO_AF10_OTG1_HS -#define GPIO_AF12_OTG2_FS GPIO_AF12_OTG1_FS -#endif /*STM32H743xx || STM32H753xx || STM32H750xx || STM32H742xx || STM32H745xx || STM32H755xx || STM32H747xx || STM32H757xx */ -#endif /* STM32H7 */ - -#define GPIO_AF0_LPTIM GPIO_AF0_LPTIM1 -#define GPIO_AF1_LPTIM GPIO_AF1_LPTIM1 -#define GPIO_AF2_LPTIM GPIO_AF2_LPTIM1 - -#if defined(STM32L0) || defined(STM32L4) || defined(STM32F4) || defined(STM32F2) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32WB) || defined(STM32U5) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_FAST GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L0 || STM32L4 || STM32F4 || STM32F2 || STM32F7 || STM32G4 || STM32H7 || STM32WB || STM32U5*/ - -#if defined(STM32L1) -#define GPIO_SPEED_VERY_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L1 */ - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F1) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_HIGH -#endif /* STM32F0 || STM32F3 || STM32F1 */ - -#define GPIO_AF6_DFSDM GPIO_AF6_DFSDM1 - -#if defined(STM32U5) -#define GPIO_AF0_RTC_50Hz GPIO_AF0_RTC_50HZ -#endif /* STM32U5 */ -#if defined(STM32U5) -#define GPIO_AF0_S2DSTOP GPIO_AF0_SRDSTOP -#define GPIO_AF11_LPGPIO GPIO_AF11_LPGPIO1 -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_GTZC_Aliased_Defines HAL GTZC Aliased Defines maintained for legacy purpose - * @{ - */ -#if defined(STM32U5) -#define GTZC_PERIPH_DCMI GTZC_PERIPH_DCMI_PSSI -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Macros HAL HRTIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define HRTIM_TIMDELAYEDPROTECTION_DISABLED HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DISABLED -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV7 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV7 - -#define __HAL_HRTIM_SetCounter __HAL_HRTIM_SETCOUNTER -#define __HAL_HRTIM_GetCounter __HAL_HRTIM_GETCOUNTER -#define __HAL_HRTIM_SetPeriod __HAL_HRTIM_SETPERIOD -#define __HAL_HRTIM_GetPeriod __HAL_HRTIM_GETPERIOD -#define __HAL_HRTIM_SetClockPrescaler __HAL_HRTIM_SETCLOCKPRESCALER -#define __HAL_HRTIM_GetClockPrescaler __HAL_HRTIM_GETCLOCKPRESCALER -#define __HAL_HRTIM_SetCompare __HAL_HRTIM_SETCOMPARE -#define __HAL_HRTIM_GetCompare __HAL_HRTIM_GETCOMPARE - -#if defined(STM32G4) -#define HAL_HRTIM_ExternalEventCounterConfig HAL_HRTIM_ExtEventCounterConfig -#define HAL_HRTIM_ExternalEventCounterEnable HAL_HRTIM_ExtEventCounterEnable -#define HAL_HRTIM_ExternalEventCounterDisable HAL_HRTIM_ExtEventCounterDisable -#define HAL_HRTIM_ExternalEventCounterReset HAL_HRTIM_ExtEventCounterReset -#define HRTIM_TIMEEVENT_A HRTIM_EVENTCOUNTER_A -#define HRTIM_TIMEEVENT_B HRTIM_EVENTCOUNTER_B -#define HRTIM_TIMEEVENTRESETMODE_UNCONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_UNCONDITIONAL -#define HRTIM_TIMEEVENTRESETMODE_CONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_CONDITIONAL -#endif /* STM32G4 */ - -#if defined(STM32H7) -#define HRTIM_OUTPUTSET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 - -#define HRTIM_OUTPUTRESET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 -#endif /* STM32H7 */ - -#if defined(STM32F3) -/** @brief Constants defining available sources associated to external events. - */ -#define HRTIM_EVENTSRC_1 (0x00000000U) -#define HRTIM_EVENTSRC_2 (HRTIM_EECR1_EE1SRC_0) -#define HRTIM_EVENTSRC_3 (HRTIM_EECR1_EE1SRC_1) -#define HRTIM_EVENTSRC_4 (HRTIM_EECR1_EE1SRC_1 | HRTIM_EECR1_EE1SRC_0) - -/** @brief Constants defining the DLL calibration periods (in micro seconds) - */ -#define HRTIM_CALIBRATIONRATE_7300 0x00000000U -#define HRTIM_CALIBRATIONRATE_910 (HRTIM_DLLCR_CALRTE_0) -#define HRTIM_CALIBRATIONRATE_114 (HRTIM_DLLCR_CALRTE_1) -#define HRTIM_CALIBRATIONRATE_14 (HRTIM_DLLCR_CALRTE_1 | HRTIM_DLLCR_CALRTE_0) - -#endif /* STM32F3 */ -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Defines HAL I2C Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2C_DUALADDRESS_DISABLED I2C_DUALADDRESS_DISABLE -#define I2C_DUALADDRESS_ENABLED I2C_DUALADDRESS_ENABLE -#define I2C_GENERALCALL_DISABLED I2C_GENERALCALL_DISABLE -#define I2C_GENERALCALL_ENABLED I2C_GENERALCALL_ENABLE -#define I2C_NOSTRETCH_DISABLED I2C_NOSTRETCH_DISABLE -#define I2C_NOSTRETCH_ENABLED I2C_NOSTRETCH_ENABLE -#define I2C_ANALOGFILTER_ENABLED I2C_ANALOGFILTER_ENABLE -#define I2C_ANALOGFILTER_DISABLED I2C_ANALOGFILTER_DISABLE -#if defined(STM32F0) || defined(STM32F1) || defined(STM32F3) || defined(STM32G0) || defined(STM32L4) || defined(STM32L1) || defined(STM32F7) -#define HAL_I2C_STATE_MEM_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MEM_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_MASTER_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MASTER_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_SLAVE_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_SLAVE_BUSY_RX HAL_I2C_STATE_BUSY_RX -#endif -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Defines HAL IRDA Aliased Defines maintained for legacy purpose - * @{ - */ -#define IRDA_ONE_BIT_SAMPLE_DISABLED IRDA_ONE_BIT_SAMPLE_DISABLE -#define IRDA_ONE_BIT_SAMPLE_ENABLED IRDA_ONE_BIT_SAMPLE_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_IWDG_Aliased_Defines HAL IWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define KR_KEY_RELOAD IWDG_KEY_RELOAD -#define KR_KEY_ENABLE IWDG_KEY_ENABLE -#define KR_KEY_EWA IWDG_KEY_WRITE_ACCESS_ENABLE -#define KR_KEY_DWA IWDG_KEY_WRITE_ACCESS_DISABLE -/** - * @} - */ - -/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose - * @{ - */ - -#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION -#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CLOCKSAMPLETIME_2TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CLOCKSAMPLETIME_4TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CLOCKSAMPLETIME_8TRANSITIONS - -#define LPTIM_CLOCKPOLARITY_RISINGEDGE LPTIM_CLOCKPOLARITY_RISING -#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CLOCKPOLARITY_FALLING -#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CLOCKPOLARITY_RISING_FALLING - -#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION -#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_TRIGSAMPLETIME_8TRANSITIONS - -/* The following 3 definition have also been present in a temporary version of lptim.h */ -/* They need to be renamed also to the right name, just in case */ -#define LPTIM_TRIGSAMPLETIME_2TRANSITION LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSITION LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSITION LPTIM_TRIGSAMPLETIME_8TRANSITIONS - - -/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_LPTIM_ReadCompare HAL_LPTIM_ReadCapturedValue -/** - * @} - */ - -#if defined(STM32U5) -#define LPTIM_ISR_CC1 LPTIM_ISR_CC1IF -#define LPTIM_ISR_CC2 LPTIM_ISR_CC2IF -#define LPTIM_CHANNEL_ALL 0x00000000U -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_NAND_Aliased_Defines HAL NAND Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_NAND_Read_Page HAL_NAND_Read_Page_8b -#define HAL_NAND_Write_Page HAL_NAND_Write_Page_8b -#define HAL_NAND_Read_SpareArea HAL_NAND_Read_SpareArea_8b -#define HAL_NAND_Write_SpareArea HAL_NAND_Write_SpareArea_8b - -#define NAND_AddressTypedef NAND_AddressTypeDef - -#define __ARRAY_ADDRESS ARRAY_ADDRESS -#define __ADDR_1st_CYCLE ADDR_1ST_CYCLE -#define __ADDR_2nd_CYCLE ADDR_2ND_CYCLE -#define __ADDR_3rd_CYCLE ADDR_3RD_CYCLE -#define __ADDR_4th_CYCLE ADDR_4TH_CYCLE -/** - * @} - */ - -/** @defgroup HAL_NOR_Aliased_Defines HAL NOR Aliased Defines maintained for legacy purpose - * @{ - */ -#define NOR_StatusTypedef HAL_NOR_StatusTypeDef -#define NOR_SUCCESS HAL_NOR_STATUS_SUCCESS -#define NOR_ONGOING HAL_NOR_STATUS_ONGOING -#define NOR_ERROR HAL_NOR_STATUS_ERROR -#define NOR_TIMEOUT HAL_NOR_STATUS_TIMEOUT - -#define __NOR_WRITE NOR_WRITE -#define __NOR_ADDR_SHIFT NOR_ADDR_SHIFT -/** - * @} - */ - -/** @defgroup HAL_OPAMP_Aliased_Defines HAL OPAMP Aliased Defines maintained for legacy purpose - * @{ - */ - -#define OPAMP_NONINVERTINGINPUT_VP0 OPAMP_NONINVERTINGINPUT_IO0 -#define OPAMP_NONINVERTINGINPUT_VP1 OPAMP_NONINVERTINGINPUT_IO1 -#define OPAMP_NONINVERTINGINPUT_VP2 OPAMP_NONINVERTINGINPUT_IO2 -#define OPAMP_NONINVERTINGINPUT_VP3 OPAMP_NONINVERTINGINPUT_IO3 - -#define OPAMP_SEC_NONINVERTINGINPUT_VP0 OPAMP_SEC_NONINVERTINGINPUT_IO0 -#define OPAMP_SEC_NONINVERTINGINPUT_VP1 OPAMP_SEC_NONINVERTINGINPUT_IO1 -#define OPAMP_SEC_NONINVERTINGINPUT_VP2 OPAMP_SEC_NONINVERTINGINPUT_IO2 -#define OPAMP_SEC_NONINVERTINGINPUT_VP3 OPAMP_SEC_NONINVERTINGINPUT_IO3 - -#define OPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define OPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define IOPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define IOPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define OPAMP_SEC_INVERTINGINPUT_VM0 OPAMP_SEC_INVERTINGINPUT_IO0 -#define OPAMP_SEC_INVERTINGINPUT_VM1 OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_INVERTINGINPUT_VINM OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_PGACONNECT_NO OPAMP_PGA_CONNECT_INVERTINGINPUT_NO -#define OPAMP_PGACONNECT_VM0 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0 -#define OPAMP_PGACONNECT_VM1 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO1 - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32L5) || defined(STM32H7) || defined(STM32G4) -#define HAL_OPAMP_MSP_INIT_CB_ID HAL_OPAMP_MSPINIT_CB_ID -#define HAL_OPAMP_MSP_DEINIT_CB_ID HAL_OPAMP_MSPDEINIT_CB_ID -#endif - -#if defined(STM32L4) || defined(STM32L5) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALPOWER -#elif defined(STM32G4) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALSPEED -#endif - -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Defines HAL I2S Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2S_STANDARD_PHILLIPS I2S_STANDARD_PHILIPS - -#if defined(STM32H7) -#define I2S_IT_TXE I2S_IT_TXP -#define I2S_IT_RXNE I2S_IT_RXP - -#define I2S_FLAG_TXE I2S_FLAG_TXP -#define I2S_FLAG_RXNE I2S_FLAG_RXP -#endif - -#if defined(STM32F7) -#define I2S_CLOCK_SYSCLK I2S_CLOCK_PLL -#endif -/** - * @} - */ - -/** @defgroup HAL_PCCARD_Aliased_Defines HAL PCCARD Aliased Defines maintained for legacy purpose - * @{ - */ - -/* Compact Flash-ATA registers description */ -#define CF_DATA ATA_DATA -#define CF_SECTOR_COUNT ATA_SECTOR_COUNT -#define CF_SECTOR_NUMBER ATA_SECTOR_NUMBER -#define CF_CYLINDER_LOW ATA_CYLINDER_LOW -#define CF_CYLINDER_HIGH ATA_CYLINDER_HIGH -#define CF_CARD_HEAD ATA_CARD_HEAD -#define CF_STATUS_CMD ATA_STATUS_CMD -#define CF_STATUS_CMD_ALTERNATE ATA_STATUS_CMD_ALTERNATE -#define CF_COMMON_DATA_AREA ATA_COMMON_DATA_AREA - -/* Compact Flash-ATA commands */ -#define CF_READ_SECTOR_CMD ATA_READ_SECTOR_CMD -#define CF_WRITE_SECTOR_CMD ATA_WRITE_SECTOR_CMD -#define CF_ERASE_SECTOR_CMD ATA_ERASE_SECTOR_CMD -#define CF_IDENTIFY_CMD ATA_IDENTIFY_CMD - -#define PCCARD_StatusTypedef HAL_PCCARD_StatusTypeDef -#define PCCARD_SUCCESS HAL_PCCARD_STATUS_SUCCESS -#define PCCARD_ONGOING HAL_PCCARD_STATUS_ONGOING -#define PCCARD_ERROR HAL_PCCARD_STATUS_ERROR -#define PCCARD_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Defines HAL RTC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FORMAT_BIN RTC_FORMAT_BIN -#define FORMAT_BCD RTC_FORMAT_BCD - -#define RTC_ALARMSUBSECONDMASK_None RTC_ALARMSUBSECONDMASK_NONE -#define RTC_TAMPERERASEBACKUP_DISABLED RTC_TAMPER_ERASE_BACKUP_DISABLE -#define RTC_TAMPERMASK_FLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_TAMPERMASK_FLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE - -#define RTC_MASKTAMPERFLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_MASKTAMPERFLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE -#define RTC_TAMPERERASEBACKUP_ENABLED RTC_TAMPER_ERASE_BACKUP_ENABLE -#define RTC_TAMPER1_2_INTERRUPT RTC_ALL_TAMPER_INTERRUPT -#define RTC_TAMPER1_2_3_INTERRUPT RTC_ALL_TAMPER_INTERRUPT - -#define RTC_TIMESTAMPPIN_PC13 RTC_TIMESTAMPPIN_DEFAULT -#define RTC_TIMESTAMPPIN_PA0 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PI8 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PC1 RTC_TIMESTAMPPIN_POS2 - -#define RTC_OUTPUT_REMAP_PC13 RTC_OUTPUT_REMAP_NONE -#define RTC_OUTPUT_REMAP_PB14 RTC_OUTPUT_REMAP_POS1 -#define RTC_OUTPUT_REMAP_PB2 RTC_OUTPUT_REMAP_POS1 - -#define RTC_TAMPERPIN_PC13 RTC_TAMPERPIN_DEFAULT -#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1 -#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1 - -#if defined(STM32F7) -#define RTC_TAMPCR_TAMPXE RTC_TAMPER_ENABLE_BITS_MASK -#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_IT_ENABLE_BITS_MASK -#endif /* STM32F7 */ - -#if defined(STM32H7) -#define RTC_TAMPCR_TAMPXE RTC_TAMPER_X -#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_X_INTERRUPT -#endif /* STM32H7 */ - -#if defined(STM32F7) || defined(STM32H7) -#define RTC_TAMPER1_INTERRUPT RTC_IT_TAMP1 -#define RTC_TAMPER2_INTERRUPT RTC_IT_TAMP2 -#define RTC_TAMPER3_INTERRUPT RTC_IT_TAMP3 -#define RTC_ALL_TAMPER_INTERRUPT RTC_IT_TAMP -#endif /* STM32F7 || STM32H7 */ - -/** - * @} - */ - - -/** @defgroup HAL_SMARTCARD_Aliased_Defines HAL SMARTCARD Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMARTCARD_NACK_ENABLED SMARTCARD_NACK_ENABLE -#define SMARTCARD_NACK_DISABLED SMARTCARD_NACK_DISABLE - -#define SMARTCARD_ONEBIT_SAMPLING_DISABLED SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLED SMARTCARD_ONE_BIT_SAMPLE_ENABLE -#define SMARTCARD_ONEBIT_SAMPLING_DISABLE SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLE SMARTCARD_ONE_BIT_SAMPLE_ENABLE - -#define SMARTCARD_TIMEOUT_DISABLED SMARTCARD_TIMEOUT_DISABLE -#define SMARTCARD_TIMEOUT_ENABLED SMARTCARD_TIMEOUT_ENABLE - -#define SMARTCARD_LASTBIT_DISABLED SMARTCARD_LASTBIT_DISABLE -#define SMARTCARD_LASTBIT_ENABLED SMARTCARD_LASTBIT_ENABLE -/** - * @} - */ - - -/** @defgroup HAL_SMBUS_Aliased_Defines HAL SMBUS Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMBUS_DUALADDRESS_DISABLED SMBUS_DUALADDRESS_DISABLE -#define SMBUS_DUALADDRESS_ENABLED SMBUS_DUALADDRESS_ENABLE -#define SMBUS_GENERALCALL_DISABLED SMBUS_GENERALCALL_DISABLE -#define SMBUS_GENERALCALL_ENABLED SMBUS_GENERALCALL_ENABLE -#define SMBUS_NOSTRETCH_DISABLED SMBUS_NOSTRETCH_DISABLE -#define SMBUS_NOSTRETCH_ENABLED SMBUS_NOSTRETCH_ENABLE -#define SMBUS_ANALOGFILTER_ENABLED SMBUS_ANALOGFILTER_ENABLE -#define SMBUS_ANALOGFILTER_DISABLED SMBUS_ANALOGFILTER_DISABLE -#define SMBUS_PEC_DISABLED SMBUS_PEC_DISABLE -#define SMBUS_PEC_ENABLED SMBUS_PEC_ENABLE -#define HAL_SMBUS_STATE_SLAVE_LISTEN HAL_SMBUS_STATE_LISTEN -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Defines HAL SPI Aliased Defines maintained for legacy purpose - * @{ - */ -#define SPI_TIMODE_DISABLED SPI_TIMODE_DISABLE -#define SPI_TIMODE_ENABLED SPI_TIMODE_ENABLE - -#define SPI_CRCCALCULATION_DISABLED SPI_CRCCALCULATION_DISABLE -#define SPI_CRCCALCULATION_ENABLED SPI_CRCCALCULATION_ENABLE - -#define SPI_NSS_PULSE_DISABLED SPI_NSS_PULSE_DISABLE -#define SPI_NSS_PULSE_ENABLED SPI_NSS_PULSE_ENABLE - -#if defined(STM32H7) - -#define SPI_FLAG_TXE SPI_FLAG_TXP -#define SPI_FLAG_RXNE SPI_FLAG_RXP - -#define SPI_IT_TXE SPI_IT_TXP -#define SPI_IT_RXNE SPI_IT_RXP - -#define SPI_FRLVL_EMPTY SPI_RX_FIFO_0PACKET -#define SPI_FRLVL_QUARTER_FULL SPI_RX_FIFO_1PACKET -#define SPI_FRLVL_HALF_FULL SPI_RX_FIFO_2PACKET -#define SPI_FRLVL_FULL SPI_RX_FIFO_3PACKET - -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Defines HAL TIM Aliased Defines maintained for legacy purpose - * @{ - */ -#define CCER_CCxE_MASK TIM_CCER_CCxE_MASK -#define CCER_CCxNE_MASK TIM_CCER_CCxNE_MASK - -#define TIM_DMABase_CR1 TIM_DMABASE_CR1 -#define TIM_DMABase_CR2 TIM_DMABASE_CR2 -#define TIM_DMABase_SMCR TIM_DMABASE_SMCR -#define TIM_DMABase_DIER TIM_DMABASE_DIER -#define TIM_DMABase_SR TIM_DMABASE_SR -#define TIM_DMABase_EGR TIM_DMABASE_EGR -#define TIM_DMABase_CCMR1 TIM_DMABASE_CCMR1 -#define TIM_DMABase_CCMR2 TIM_DMABASE_CCMR2 -#define TIM_DMABase_CCER TIM_DMABASE_CCER -#define TIM_DMABase_CNT TIM_DMABASE_CNT -#define TIM_DMABase_PSC TIM_DMABASE_PSC -#define TIM_DMABase_ARR TIM_DMABASE_ARR -#define TIM_DMABase_RCR TIM_DMABASE_RCR -#define TIM_DMABase_CCR1 TIM_DMABASE_CCR1 -#define TIM_DMABase_CCR2 TIM_DMABASE_CCR2 -#define TIM_DMABase_CCR3 TIM_DMABASE_CCR3 -#define TIM_DMABase_CCR4 TIM_DMABASE_CCR4 -#define TIM_DMABase_BDTR TIM_DMABASE_BDTR -#define TIM_DMABase_DCR TIM_DMABASE_DCR -#define TIM_DMABase_DMAR TIM_DMABASE_DMAR -#define TIM_DMABase_OR1 TIM_DMABASE_OR1 -#define TIM_DMABase_CCMR3 TIM_DMABASE_CCMR3 -#define TIM_DMABase_CCR5 TIM_DMABASE_CCR5 -#define TIM_DMABase_CCR6 TIM_DMABASE_CCR6 -#define TIM_DMABase_OR2 TIM_DMABASE_OR2 -#define TIM_DMABase_OR3 TIM_DMABASE_OR3 -#define TIM_DMABase_OR TIM_DMABASE_OR - -#define TIM_EventSource_Update TIM_EVENTSOURCE_UPDATE -#define TIM_EventSource_CC1 TIM_EVENTSOURCE_CC1 -#define TIM_EventSource_CC2 TIM_EVENTSOURCE_CC2 -#define TIM_EventSource_CC3 TIM_EVENTSOURCE_CC3 -#define TIM_EventSource_CC4 TIM_EVENTSOURCE_CC4 -#define TIM_EventSource_COM TIM_EVENTSOURCE_COM -#define TIM_EventSource_Trigger TIM_EVENTSOURCE_TRIGGER -#define TIM_EventSource_Break TIM_EVENTSOURCE_BREAK -#define TIM_EventSource_Break2 TIM_EVENTSOURCE_BREAK2 - -#define TIM_DMABurstLength_1Transfer TIM_DMABURSTLENGTH_1TRANSFER -#define TIM_DMABurstLength_2Transfers TIM_DMABURSTLENGTH_2TRANSFERS -#define TIM_DMABurstLength_3Transfers TIM_DMABURSTLENGTH_3TRANSFERS -#define TIM_DMABurstLength_4Transfers TIM_DMABURSTLENGTH_4TRANSFERS -#define TIM_DMABurstLength_5Transfers TIM_DMABURSTLENGTH_5TRANSFERS -#define TIM_DMABurstLength_6Transfers TIM_DMABURSTLENGTH_6TRANSFERS -#define TIM_DMABurstLength_7Transfers TIM_DMABURSTLENGTH_7TRANSFERS -#define TIM_DMABurstLength_8Transfers TIM_DMABURSTLENGTH_8TRANSFERS -#define TIM_DMABurstLength_9Transfers TIM_DMABURSTLENGTH_9TRANSFERS -#define TIM_DMABurstLength_10Transfers TIM_DMABURSTLENGTH_10TRANSFERS -#define TIM_DMABurstLength_11Transfers TIM_DMABURSTLENGTH_11TRANSFERS -#define TIM_DMABurstLength_12Transfers TIM_DMABURSTLENGTH_12TRANSFERS -#define TIM_DMABurstLength_13Transfers TIM_DMABURSTLENGTH_13TRANSFERS -#define TIM_DMABurstLength_14Transfers TIM_DMABURSTLENGTH_14TRANSFERS -#define TIM_DMABurstLength_15Transfers TIM_DMABURSTLENGTH_15TRANSFERS -#define TIM_DMABurstLength_16Transfers TIM_DMABURSTLENGTH_16TRANSFERS -#define TIM_DMABurstLength_17Transfers TIM_DMABURSTLENGTH_17TRANSFERS -#define TIM_DMABurstLength_18Transfers TIM_DMABURSTLENGTH_18TRANSFERS - -#if defined(STM32L0) -#define TIM22_TI1_GPIO1 TIM22_TI1_GPIO -#define TIM22_TI1_GPIO2 TIM22_TI1_GPIO -#endif - -#if defined(STM32F3) -#define IS_TIM_HALL_INTERFACE_INSTANCE IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE -#endif - -#if defined(STM32H7) -#define TIM_TIM1_ETR_COMP1_OUT TIM_TIM1_ETR_COMP1 -#define TIM_TIM1_ETR_COMP2_OUT TIM_TIM1_ETR_COMP2 -#define TIM_TIM8_ETR_COMP1_OUT TIM_TIM8_ETR_COMP1 -#define TIM_TIM8_ETR_COMP2_OUT TIM_TIM8_ETR_COMP2 -#define TIM_TIM2_ETR_COMP1_OUT TIM_TIM2_ETR_COMP1 -#define TIM_TIM2_ETR_COMP2_OUT TIM_TIM2_ETR_COMP2 -#define TIM_TIM3_ETR_COMP1_OUT TIM_TIM3_ETR_COMP1 -#define TIM_TIM1_TI1_COMP1_OUT TIM_TIM1_TI1_COMP1 -#define TIM_TIM8_TI1_COMP2_OUT TIM_TIM8_TI1_COMP2 -#define TIM_TIM2_TI4_COMP1_OUT TIM_TIM2_TI4_COMP1 -#define TIM_TIM2_TI4_COMP2_OUT TIM_TIM2_TI4_COMP2 -#define TIM_TIM2_TI4_COMP1COMP2_OUT TIM_TIM2_TI4_COMP1_COMP2 -#define TIM_TIM3_TI1_COMP1_OUT TIM_TIM3_TI1_COMP1 -#define TIM_TIM3_TI1_COMP2_OUT TIM_TIM3_TI1_COMP2 -#define TIM_TIM3_TI1_COMP1COMP2_OUT TIM_TIM3_TI1_COMP1_COMP2 -#endif - -#if defined(STM32U5) || defined(STM32MP2) -#define OCREF_CLEAR_SELECT_Pos OCREF_CLEAR_SELECT_POS -#define OCREF_CLEAR_SELECT_Msk OCREF_CLEAR_SELECT_MSK -#endif -/** - * @} - */ - -/** @defgroup HAL_TSC_Aliased_Defines HAL TSC Aliased Defines maintained for legacy purpose - * @{ - */ -#define TSC_SYNC_POL_FALL TSC_SYNC_POLARITY_FALLING -#define TSC_SYNC_POL_RISE_HIGH TSC_SYNC_POLARITY_RISING -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Defines HAL UART Aliased Defines maintained for legacy purpose - * @{ - */ -#define UART_ONEBIT_SAMPLING_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONEBIT_SAMPLING_ENABLED UART_ONE_BIT_SAMPLE_ENABLE -#define UART_ONE_BIT_SAMPLE_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONE_BIT_SAMPLE_ENABLED UART_ONE_BIT_SAMPLE_ENABLE - -#define __HAL_UART_ONEBIT_ENABLE __HAL_UART_ONE_BIT_SAMPLE_ENABLE -#define __HAL_UART_ONEBIT_DISABLE __HAL_UART_ONE_BIT_SAMPLE_DISABLE - -#define __DIV_SAMPLING16 UART_DIV_SAMPLING16 -#define __DIVMANT_SAMPLING16 UART_DIVMANT_SAMPLING16 -#define __DIVFRAQ_SAMPLING16 UART_DIVFRAQ_SAMPLING16 -#define __UART_BRR_SAMPLING16 UART_BRR_SAMPLING16 - -#define __DIV_SAMPLING8 UART_DIV_SAMPLING8 -#define __DIVMANT_SAMPLING8 UART_DIVMANT_SAMPLING8 -#define __DIVFRAQ_SAMPLING8 UART_DIVFRAQ_SAMPLING8 -#define __UART_BRR_SAMPLING8 UART_BRR_SAMPLING8 - -#define __DIV_LPUART UART_DIV_LPUART - -#define UART_WAKEUPMETHODE_IDLELINE UART_WAKEUPMETHOD_IDLELINE -#define UART_WAKEUPMETHODE_ADDRESSMARK UART_WAKEUPMETHOD_ADDRESSMARK - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Defines HAL USART Aliased Defines maintained for legacy purpose - * @{ - */ - -#define USART_CLOCK_DISABLED USART_CLOCK_DISABLE -#define USART_CLOCK_ENABLED USART_CLOCK_ENABLE - -#define USARTNACK_ENABLED USART_NACK_ENABLE -#define USARTNACK_DISABLED USART_NACK_DISABLE -/** - * @} - */ - -/** @defgroup HAL_WWDG_Aliased_Defines HAL WWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define CFR_BASE WWDG_CFR_BASE - -/** - * @} - */ - -/** @defgroup HAL_CAN_Aliased_Defines HAL CAN Aliased Defines maintained for legacy purpose - * @{ - */ -#define CAN_FilterFIFO0 CAN_FILTER_FIFO0 -#define CAN_FilterFIFO1 CAN_FILTER_FIFO1 -#define CAN_IT_RQCP0 CAN_IT_TME -#define CAN_IT_RQCP1 CAN_IT_TME -#define CAN_IT_RQCP2 CAN_IT_TME -#define INAK_TIMEOUT CAN_TIMEOUT_VALUE -#define SLAK_TIMEOUT CAN_TIMEOUT_VALUE -#define CAN_TXSTATUS_FAILED ((uint8_t)0x00U) -#define CAN_TXSTATUS_OK ((uint8_t)0x01U) -#define CAN_TXSTATUS_PENDING ((uint8_t)0x02U) - -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Defines HAL ETH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define VLAN_TAG ETH_VLAN_TAG -#define MIN_ETH_PAYLOAD ETH_MIN_ETH_PAYLOAD -#define MAX_ETH_PAYLOAD ETH_MAX_ETH_PAYLOAD -#define JUMBO_FRAME_PAYLOAD ETH_JUMBO_FRAME_PAYLOAD -#define MACMIIAR_CR_MASK ETH_MACMIIAR_CR_MASK -#define MACCR_CLEAR_MASK ETH_MACCR_CLEAR_MASK -#define MACFCR_CLEAR_MASK ETH_MACFCR_CLEAR_MASK -#define DMAOMR_CLEAR_MASK ETH_DMAOMR_CLEAR_MASK - -#define ETH_MMCCR 0x00000100U -#define ETH_MMCRIR 0x00000104U -#define ETH_MMCTIR 0x00000108U -#define ETH_MMCRIMR 0x0000010CU -#define ETH_MMCTIMR 0x00000110U -#define ETH_MMCTGFSCCR 0x0000014CU -#define ETH_MMCTGFMSCCR 0x00000150U -#define ETH_MMCTGFCR 0x00000168U -#define ETH_MMCRFCECR 0x00000194U -#define ETH_MMCRFAECR 0x00000198U -#define ETH_MMCRGUFCR 0x000001C4U - -#define ETH_MAC_TXFIFO_FULL 0x02000000U /* Tx FIFO full */ -#define ETH_MAC_TXFIFONOT_EMPTY 0x01000000U /* Tx FIFO not empty */ -#define ETH_MAC_TXFIFO_WRITE_ACTIVE 0x00400000U /* Tx FIFO write active */ -#define ETH_MAC_TXFIFO_IDLE 0x00000000U /* Tx FIFO read status: Idle */ -#define ETH_MAC_TXFIFO_READ 0x00100000U /* Tx FIFO read status: Read (transferring data to the MAC transmitter) */ -#define ETH_MAC_TXFIFO_WAITING 0x00200000U /* Tx FIFO read status: Waiting for TxStatus from MAC transmitter */ -#define ETH_MAC_TXFIFO_WRITING 0x00300000U /* Tx FIFO read status: Writing the received TxStatus or flushing the TxFIFO */ -#define ETH_MAC_TRANSMISSION_PAUSE 0x00080000U /* MAC transmitter in pause */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_IDLE 0x00000000U /* MAC transmit frame controller: Idle */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_WAITING 0x00020000U /* MAC transmit frame controller: Waiting for Status of previous frame or IFG/backoff period to be over */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_GENRATING_PCF 0x00040000U /* MAC transmit frame controller: Generating and transmitting a Pause control frame (in full duplex mode) */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_TRANSFERRING 0x00060000U /* MAC transmit frame controller: Transferring input frame for transmission */ -#define ETH_MAC_MII_TRANSMIT_ACTIVE 0x00010000U /* MAC MII transmit engine active */ -#define ETH_MAC_RXFIFO_EMPTY 0x00000000U /* Rx FIFO fill level: empty */ -#define ETH_MAC_RXFIFO_BELOW_THRESHOLD 0x00000100U /* Rx FIFO fill level: fill-level below flow-control de-activate threshold */ -#define ETH_MAC_RXFIFO_ABOVE_THRESHOLD 0x00000200U /* Rx FIFO fill level: fill-level above flow-control activate threshold */ -#define ETH_MAC_RXFIFO_FULL 0x00000300U /* Rx FIFO fill level: full */ -#if defined(STM32F1) -#else -#define ETH_MAC_READCONTROLLER_IDLE 0x00000000U /* Rx FIFO read controller IDLE state */ -#define ETH_MAC_READCONTROLLER_READING_DATA 0x00000020U /* Rx FIFO read controller Reading frame data */ -#define ETH_MAC_READCONTROLLER_READING_STATUS 0x00000040U /* Rx FIFO read controller Reading frame status (or time-stamp) */ -#endif -#define ETH_MAC_READCONTROLLER_FLUSHING 0x00000060U /* Rx FIFO read controller Flushing the frame data and status */ -#define ETH_MAC_RXFIFO_WRITE_ACTIVE 0x00000010U /* Rx FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_NOTACTIVE 0x00000000U /* MAC small FIFO read / write controllers not active */ -#define ETH_MAC_SMALL_FIFO_READ_ACTIVE 0x00000002U /* MAC small FIFO read controller active */ -#define ETH_MAC_SMALL_FIFO_WRITE_ACTIVE 0x00000004U /* MAC small FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */ -#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */ - -/** - * @} - */ - -/** @defgroup HAL_DCMI_Aliased_Defines HAL DCMI Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_DCMI_ERROR_OVF HAL_DCMI_ERROR_OVR -#define DCMI_IT_OVF DCMI_IT_OVR -#define DCMI_FLAG_OVFRI DCMI_FLAG_OVRRI -#define DCMI_FLAG_OVFMI DCMI_FLAG_OVRMI - -#define HAL_DCMI_ConfigCROP HAL_DCMI_ConfigCrop -#define HAL_DCMI_EnableCROP HAL_DCMI_EnableCrop -#define HAL_DCMI_DisableCROP HAL_DCMI_DisableCrop - -/** - * @} - */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) -/** @defgroup HAL_DMA2D_Aliased_Defines HAL DMA2D Aliased Defines maintained for legacy purpose - * @{ - */ -#define DMA2D_ARGB8888 DMA2D_OUTPUT_ARGB8888 -#define DMA2D_RGB888 DMA2D_OUTPUT_RGB888 -#define DMA2D_RGB565 DMA2D_OUTPUT_RGB565 -#define DMA2D_ARGB1555 DMA2D_OUTPUT_ARGB1555 -#define DMA2D_ARGB4444 DMA2D_OUTPUT_ARGB4444 - -#define CM_ARGB8888 DMA2D_INPUT_ARGB8888 -#define CM_RGB888 DMA2D_INPUT_RGB888 -#define CM_RGB565 DMA2D_INPUT_RGB565 -#define CM_ARGB1555 DMA2D_INPUT_ARGB1555 -#define CM_ARGB4444 DMA2D_INPUT_ARGB4444 -#define CM_L8 DMA2D_INPUT_L8 -#define CM_AL44 DMA2D_INPUT_AL44 -#define CM_AL88 DMA2D_INPUT_AL88 -#define CM_L4 DMA2D_INPUT_L4 -#define CM_A8 DMA2D_INPUT_A8 -#define CM_A4 DMA2D_INPUT_A4 -/** - * @} - */ -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) || defined(STM32U5) -/** @defgroup DMA2D_Aliases DMA2D API Aliases - * @{ - */ -#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort - for compatibility with legacy code */ -/** - * @} - */ - -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 || STM32U5 */ - -/** @defgroup HAL_PPP_Aliased_Defines HAL PPP Aliased Defines maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup HAL_CRYP_Aliased_Functions HAL CRYP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback -/** - * @} - */ - -/** @defgroup HAL_DCACHE_Aliased_Functions HAL DCACHE Aliased Functions maintained for legacy purpose - * @{ - */ - -#if defined(STM32U5) -#define HAL_DCACHE_CleanInvalidateByAddr HAL_DCACHE_CleanInvalidByAddr -#define HAL_DCACHE_CleanInvalidateByAddr_IT HAL_DCACHE_CleanInvalidByAddr_IT -#endif /* STM32U5 */ - -/** - * @} - */ - -#if !defined(STM32F2) -/** @defgroup HASH_alias HASH API alias - * @{ - */ -#define HAL_HASHEx_IRQHandler HAL_HASH_IRQHandler /*!< Redirection for compatibility with legacy code */ -/** - * - * @} - */ -#endif /* STM32F2 */ -/** @defgroup HAL_HASH_Aliased_Functions HAL HASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_HASH_STATETypeDef HAL_HASH_StateTypeDef -#define HAL_HASHPhaseTypeDef HAL_HASH_PhaseTypeDef -#define HAL_HMAC_MD5_Finish HAL_HASH_MD5_Finish -#define HAL_HMAC_SHA1_Finish HAL_HASH_SHA1_Finish -#define HAL_HMAC_SHA224_Finish HAL_HASH_SHA224_Finish -#define HAL_HMAC_SHA256_Finish HAL_HASH_SHA256_Finish - -/*HASH Algorithm Selection*/ - -#define HASH_AlgoSelection_SHA1 HASH_ALGOSELECTION_SHA1 -#define HASH_AlgoSelection_SHA224 HASH_ALGOSELECTION_SHA224 -#define HASH_AlgoSelection_SHA256 HASH_ALGOSELECTION_SHA256 -#define HASH_AlgoSelection_MD5 HASH_ALGOSELECTION_MD5 - -#define HASH_AlgoMode_HASH HASH_ALGOMODE_HASH -#define HASH_AlgoMode_HMAC HASH_ALGOMODE_HMAC - -#define HASH_HMACKeyType_ShortKey HASH_HMAC_KEYTYPE_SHORTKEY -#define HASH_HMACKeyType_LongKey HASH_HMAC_KEYTYPE_LONGKEY - -#if defined(STM32L4) || defined(STM32L5) || defined(STM32F2) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - -#define HAL_HASH_MD5_Accumulate HAL_HASH_MD5_Accmlt -#define HAL_HASH_MD5_Accumulate_End HAL_HASH_MD5_Accmlt_End -#define HAL_HASH_MD5_Accumulate_IT HAL_HASH_MD5_Accmlt_IT -#define HAL_HASH_MD5_Accumulate_End_IT HAL_HASH_MD5_Accmlt_End_IT - -#define HAL_HASH_SHA1_Accumulate HAL_HASH_SHA1_Accmlt -#define HAL_HASH_SHA1_Accumulate_End HAL_HASH_SHA1_Accmlt_End -#define HAL_HASH_SHA1_Accumulate_IT HAL_HASH_SHA1_Accmlt_IT -#define HAL_HASH_SHA1_Accumulate_End_IT HAL_HASH_SHA1_Accmlt_End_IT - -#define HAL_HASHEx_SHA224_Accumulate HAL_HASHEx_SHA224_Accmlt -#define HAL_HASHEx_SHA224_Accumulate_End HAL_HASHEx_SHA224_Accmlt_End -#define HAL_HASHEx_SHA224_Accumulate_IT HAL_HASHEx_SHA224_Accmlt_IT -#define HAL_HASHEx_SHA224_Accumulate_End_IT HAL_HASHEx_SHA224_Accmlt_End_IT - -#define HAL_HASHEx_SHA256_Accumulate HAL_HASHEx_SHA256_Accmlt -#define HAL_HASHEx_SHA256_Accumulate_End HAL_HASHEx_SHA256_Accmlt_End -#define HAL_HASHEx_SHA256_Accumulate_IT HAL_HASHEx_SHA256_Accmlt_IT -#define HAL_HASHEx_SHA256_Accumulate_End_IT HAL_HASHEx_SHA256_Accmlt_End_IT - -#endif /* STM32L4 || STM32L5 || STM32F2 || STM32F4 || STM32F7 || STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_Aliased_Functions HAL Generic Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_EnableDBGSleepMode HAL_DBGMCU_EnableDBGSleepMode -#define HAL_DisableDBGSleepMode HAL_DBGMCU_DisableDBGSleepMode -#define HAL_EnableDBGStopMode HAL_DBGMCU_EnableDBGStopMode -#define HAL_DisableDBGStopMode HAL_DBGMCU_DisableDBGStopMode -#define HAL_EnableDBGStandbyMode HAL_DBGMCU_EnableDBGStandbyMode -#define HAL_DisableDBGStandbyMode HAL_DBGMCU_DisableDBGStandbyMode -#define HAL_DBG_LowPowerConfig(Periph, cmd) (((cmd\ - )==ENABLE)? HAL_DBGMCU_DBG_EnableLowPowerConfig(Periph) : HAL_DBGMCU_DBG_DisableLowPowerConfig(Periph)) -#define HAL_VREFINT_OutputSelect HAL_SYSCFG_VREFINT_OutputSelect -#define HAL_Lock_Cmd(cmd) (((cmd)==ENABLE) ? HAL_SYSCFG_Enable_Lock_VREFINT() : HAL_SYSCFG_Disable_Lock_VREFINT()) -#if defined(STM32L0) -#else -#define HAL_VREFINT_Cmd(cmd) (((cmd)==ENABLE)? HAL_SYSCFG_EnableVREFINT() : HAL_SYSCFG_DisableVREFINT()) -#endif -#define HAL_ADC_EnableBuffer_Cmd(cmd) (((cmd)==ENABLE) ? HAL_ADCEx_EnableVREFINT() : HAL_ADCEx_DisableVREFINT()) -#define HAL_ADC_EnableBufferSensor_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_ADCEx_EnableVREFINTTempSensor() : HAL_ADCEx_DisableVREFINTTempSensor()) -#if defined(STM32H7A3xx) || defined(STM32H7B3xx) || defined(STM32H7B0xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xxQ) || defined(STM32H7B0xxQ) -#define HAL_EnableSRDomainDBGStopMode HAL_EnableDomain3DBGStopMode -#define HAL_DisableSRDomainDBGStopMode HAL_DisableDomain3DBGStopMode -#define HAL_EnableSRDomainDBGStandbyMode HAL_EnableDomain3DBGStandbyMode -#define HAL_DisableSRDomainDBGStandbyMode HAL_DisableDomain3DBGStandbyMode -#endif /* STM32H7A3xx || STM32H7B3xx || STM32H7B0xx || STM32H7A3xxQ || STM32H7B3xxQ || STM32H7B0xxQ */ - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Functions HAL FLASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram -#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown -#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown -#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock -#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock -#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase -#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Functions HAL I2C Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_I2CEx_AnalogFilter_Config HAL_I2CEx_ConfigAnalogFilter -#define HAL_I2CEx_DigitalFilter_Config HAL_I2CEx_ConfigDigitalFilter -#define HAL_FMPI2CEx_AnalogFilter_Config HAL_FMPI2CEx_ConfigAnalogFilter -#define HAL_FMPI2CEx_DigitalFilter_Config HAL_FMPI2CEx_ConfigDigitalFilter - -#define HAL_I2CFastModePlusConfig(SYSCFG_I2CFastModePlus, cmd) (((cmd\ - )==ENABLE)? HAL_I2CEx_EnableFastModePlus(SYSCFG_I2CFastModePlus): HAL_I2CEx_DisableFastModePlus(SYSCFG_I2CFastModePlus)) - -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4) || defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_IT HAL_I2C_Master_Seq_Transmit_IT -#define HAL_I2C_Master_Sequential_Receive_IT HAL_I2C_Master_Seq_Receive_IT -#define HAL_I2C_Slave_Sequential_Transmit_IT HAL_I2C_Slave_Seq_Transmit_IT -#define HAL_I2C_Slave_Sequential_Receive_IT HAL_I2C_Slave_Seq_Receive_IT -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4)|| defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_DMA HAL_I2C_Master_Seq_Transmit_DMA -#define HAL_I2C_Master_Sequential_Receive_DMA HAL_I2C_Master_Seq_Receive_DMA -#define HAL_I2C_Slave_Sequential_Transmit_DMA HAL_I2C_Slave_Seq_Transmit_DMA -#define HAL_I2C_Slave_Sequential_Receive_DMA HAL_I2C_Slave_Seq_Receive_DMA -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ - -#if defined(STM32F4) -#define HAL_FMPI2C_Master_Sequential_Transmit_IT HAL_FMPI2C_Master_Seq_Transmit_IT -#define HAL_FMPI2C_Master_Sequential_Receive_IT HAL_FMPI2C_Master_Seq_Receive_IT -#define HAL_FMPI2C_Slave_Sequential_Transmit_IT HAL_FMPI2C_Slave_Seq_Transmit_IT -#define HAL_FMPI2C_Slave_Sequential_Receive_IT HAL_FMPI2C_Slave_Seq_Receive_IT -#define HAL_FMPI2C_Master_Sequential_Transmit_DMA HAL_FMPI2C_Master_Seq_Transmit_DMA -#define HAL_FMPI2C_Master_Sequential_Receive_DMA HAL_FMPI2C_Master_Seq_Receive_DMA -#define HAL_FMPI2C_Slave_Sequential_Transmit_DMA HAL_FMPI2C_Slave_Seq_Transmit_DMA -#define HAL_FMPI2C_Slave_Sequential_Receive_DMA HAL_FMPI2C_Slave_Seq_Receive_DMA -#endif /* STM32F4 */ -/** - * @} - */ - -/** @defgroup HAL_PWR_Aliased HAL PWR Aliased maintained for legacy purpose - * @{ - */ - -#if defined(STM32G0) -#define HAL_PWR_ConfigPVD HAL_PWREx_ConfigPVD -#define HAL_PWR_EnablePVD HAL_PWREx_EnablePVD -#define HAL_PWR_DisablePVD HAL_PWREx_DisablePVD -#define HAL_PWR_PVD_IRQHandler HAL_PWREx_PVD_IRQHandler -#endif -#define HAL_PWR_PVDConfig HAL_PWR_ConfigPVD -#define HAL_PWR_DisableBkUpReg HAL_PWREx_DisableBkUpReg -#define HAL_PWR_DisableFlashPowerDown HAL_PWREx_DisableFlashPowerDown -#define HAL_PWR_DisableVddio2Monitor HAL_PWREx_DisableVddio2Monitor -#define HAL_PWR_EnableBkUpReg HAL_PWREx_EnableBkUpReg -#define HAL_PWR_EnableFlashPowerDown HAL_PWREx_EnableFlashPowerDown -#define HAL_PWR_EnableVddio2Monitor HAL_PWREx_EnableVddio2Monitor -#define HAL_PWR_PVD_PVM_IRQHandler HAL_PWREx_PVD_PVM_IRQHandler -#define HAL_PWR_PVDLevelConfig HAL_PWR_ConfigPVD -#define HAL_PWR_Vddio2Monitor_IRQHandler HAL_PWREx_Vddio2Monitor_IRQHandler -#define HAL_PWR_Vddio2MonitorCallback HAL_PWREx_Vddio2MonitorCallback -#define HAL_PWREx_ActivateOverDrive HAL_PWREx_EnableOverDrive -#define HAL_PWREx_DeactivateOverDrive HAL_PWREx_DisableOverDrive -#define HAL_PWREx_DisableSDADCAnalog HAL_PWREx_DisableSDADC -#define HAL_PWREx_EnableSDADCAnalog HAL_PWREx_EnableSDADC -#define HAL_PWREx_PVMConfig HAL_PWREx_ConfigPVM - -#define PWR_MODE_NORMAL PWR_PVD_MODE_NORMAL -#define PWR_MODE_IT_RISING PWR_PVD_MODE_IT_RISING -#define PWR_MODE_IT_FALLING PWR_PVD_MODE_IT_FALLING -#define PWR_MODE_IT_RISING_FALLING PWR_PVD_MODE_IT_RISING_FALLING -#define PWR_MODE_EVENT_RISING PWR_PVD_MODE_EVENT_RISING -#define PWR_MODE_EVENT_FALLING PWR_PVD_MODE_EVENT_FALLING -#define PWR_MODE_EVENT_RISING_FALLING PWR_PVD_MODE_EVENT_RISING_FALLING - -#define CR_OFFSET_BB PWR_CR_OFFSET_BB -#define CSR_OFFSET_BB PWR_CSR_OFFSET_BB -#define PMODE_BIT_NUMBER VOS_BIT_NUMBER -#define CR_PMODE_BB CR_VOS_BB - -#define DBP_BitNumber DBP_BIT_NUMBER -#define PVDE_BitNumber PVDE_BIT_NUMBER -#define PMODE_BitNumber PMODE_BIT_NUMBER -#define EWUP_BitNumber EWUP_BIT_NUMBER -#define FPDS_BitNumber FPDS_BIT_NUMBER -#define ODEN_BitNumber ODEN_BIT_NUMBER -#define ODSWEN_BitNumber ODSWEN_BIT_NUMBER -#define MRLVDS_BitNumber MRLVDS_BIT_NUMBER -#define LPLVDS_BitNumber LPLVDS_BIT_NUMBER -#define BRE_BitNumber BRE_BIT_NUMBER - -#define PWR_MODE_EVT PWR_PVD_MODE_NORMAL - -#if defined (STM32U5) -#define PWR_SRAM1_PAGE1_STOP_RETENTION PWR_SRAM1_PAGE1_STOP -#define PWR_SRAM1_PAGE2_STOP_RETENTION PWR_SRAM1_PAGE2_STOP -#define PWR_SRAM1_PAGE3_STOP_RETENTION PWR_SRAM1_PAGE3_STOP -#define PWR_SRAM1_PAGE4_STOP_RETENTION PWR_SRAM1_PAGE4_STOP -#define PWR_SRAM1_PAGE5_STOP_RETENTION PWR_SRAM1_PAGE5_STOP -#define PWR_SRAM1_PAGE6_STOP_RETENTION PWR_SRAM1_PAGE6_STOP -#define PWR_SRAM1_PAGE7_STOP_RETENTION PWR_SRAM1_PAGE7_STOP -#define PWR_SRAM1_PAGE8_STOP_RETENTION PWR_SRAM1_PAGE8_STOP -#define PWR_SRAM1_PAGE9_STOP_RETENTION PWR_SRAM1_PAGE9_STOP -#define PWR_SRAM1_PAGE10_STOP_RETENTION PWR_SRAM1_PAGE10_STOP -#define PWR_SRAM1_PAGE11_STOP_RETENTION PWR_SRAM1_PAGE11_STOP -#define PWR_SRAM1_PAGE12_STOP_RETENTION PWR_SRAM1_PAGE12_STOP -#define PWR_SRAM1_FULL_STOP_RETENTION PWR_SRAM1_FULL_STOP - -#define PWR_SRAM2_PAGE1_STOP_RETENTION PWR_SRAM2_PAGE1_STOP -#define PWR_SRAM2_PAGE2_STOP_RETENTION PWR_SRAM2_PAGE2_STOP -#define PWR_SRAM2_FULL_STOP_RETENTION PWR_SRAM2_FULL_STOP - -#define PWR_SRAM3_PAGE1_STOP_RETENTION PWR_SRAM3_PAGE1_STOP -#define PWR_SRAM3_PAGE2_STOP_RETENTION PWR_SRAM3_PAGE2_STOP -#define PWR_SRAM3_PAGE3_STOP_RETENTION PWR_SRAM3_PAGE3_STOP -#define PWR_SRAM3_PAGE4_STOP_RETENTION PWR_SRAM3_PAGE4_STOP -#define PWR_SRAM3_PAGE5_STOP_RETENTION PWR_SRAM3_PAGE5_STOP -#define PWR_SRAM3_PAGE6_STOP_RETENTION PWR_SRAM3_PAGE6_STOP -#define PWR_SRAM3_PAGE7_STOP_RETENTION PWR_SRAM3_PAGE7_STOP -#define PWR_SRAM3_PAGE8_STOP_RETENTION PWR_SRAM3_PAGE8_STOP -#define PWR_SRAM3_PAGE9_STOP_RETENTION PWR_SRAM3_PAGE9_STOP -#define PWR_SRAM3_PAGE10_STOP_RETENTION PWR_SRAM3_PAGE10_STOP -#define PWR_SRAM3_PAGE11_STOP_RETENTION PWR_SRAM3_PAGE11_STOP -#define PWR_SRAM3_PAGE12_STOP_RETENTION PWR_SRAM3_PAGE12_STOP -#define PWR_SRAM3_PAGE13_STOP_RETENTION PWR_SRAM3_PAGE13_STOP -#define PWR_SRAM3_FULL_STOP_RETENTION PWR_SRAM3_FULL_STOP - -#define PWR_SRAM4_FULL_STOP_RETENTION PWR_SRAM4_FULL_STOP - -#define PWR_SRAM5_PAGE1_STOP_RETENTION PWR_SRAM5_PAGE1_STOP -#define PWR_SRAM5_PAGE2_STOP_RETENTION PWR_SRAM5_PAGE2_STOP -#define PWR_SRAM5_PAGE3_STOP_RETENTION PWR_SRAM5_PAGE3_STOP -#define PWR_SRAM5_PAGE4_STOP_RETENTION PWR_SRAM5_PAGE4_STOP -#define PWR_SRAM5_PAGE5_STOP_RETENTION PWR_SRAM5_PAGE5_STOP -#define PWR_SRAM5_PAGE6_STOP_RETENTION PWR_SRAM5_PAGE6_STOP -#define PWR_SRAM5_PAGE7_STOP_RETENTION PWR_SRAM5_PAGE7_STOP -#define PWR_SRAM5_PAGE8_STOP_RETENTION PWR_SRAM5_PAGE8_STOP -#define PWR_SRAM5_PAGE9_STOP_RETENTION PWR_SRAM5_PAGE9_STOP -#define PWR_SRAM5_PAGE10_STOP_RETENTION PWR_SRAM5_PAGE10_STOP -#define PWR_SRAM5_PAGE11_STOP_RETENTION PWR_SRAM5_PAGE11_STOP -#define PWR_SRAM5_PAGE12_STOP_RETENTION PWR_SRAM5_PAGE12_STOP -#define PWR_SRAM5_PAGE13_STOP_RETENTION PWR_SRAM5_PAGE13_STOP -#define PWR_SRAM5_FULL_STOP_RETENTION PWR_SRAM5_FULL_STOP - -#define PWR_ICACHE_FULL_STOP_RETENTION PWR_ICACHE_FULL_STOP -#define PWR_DCACHE1_FULL_STOP_RETENTION PWR_DCACHE1_FULL_STOP -#define PWR_DCACHE2_FULL_STOP_RETENTION PWR_DCACHE2_FULL_STOP -#define PWR_DMA2DRAM_FULL_STOP_RETENTION PWR_DMA2DRAM_FULL_STOP -#define PWR_PERIPHRAM_FULL_STOP_RETENTION PWR_PERIPHRAM_FULL_STOP -#define PWR_PKA32RAM_FULL_STOP_RETENTION PWR_PKA32RAM_FULL_STOP -#define PWR_GRAPHICPRAM_FULL_STOP_RETENTION PWR_GRAPHICPRAM_FULL_STOP -#define PWR_DSIRAM_FULL_STOP_RETENTION PWR_DSIRAM_FULL_STOP - -#define PWR_SRAM2_PAGE1_STANDBY_RETENTION PWR_SRAM2_PAGE1_STANDBY -#define PWR_SRAM2_PAGE2_STANDBY_RETENTION PWR_SRAM2_PAGE2_STANDBY -#define PWR_SRAM2_FULL_STANDBY_RETENTION PWR_SRAM2_FULL_STANDBY - -#define PWR_SRAM1_FULL_RUN_RETENTION PWR_SRAM1_FULL_RUN -#define PWR_SRAM2_FULL_RUN_RETENTION PWR_SRAM2_FULL_RUN -#define PWR_SRAM3_FULL_RUN_RETENTION PWR_SRAM3_FULL_RUN -#define PWR_SRAM4_FULL_RUN_RETENTION PWR_SRAM4_FULL_RUN -#define PWR_SRAM5_FULL_RUN_RETENTION PWR_SRAM5_FULL_RUN - -#define PWR_ALL_RAM_RUN_RETENTION_MASK PWR_ALL_RAM_RUN_MASK -#endif - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Functions HAL SMBUS Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT -#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback -#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Functions HAL SPI Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SPI_FlushRxFifo HAL_SPIEx_FlushRxFifo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Functions HAL TIM Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_TIM_DMADelayPulseCplt TIM_DMADelayPulseCplt -#define HAL_TIM_DMAError TIM_DMAError -#define HAL_TIM_DMACaptureCplt TIM_DMACaptureCplt -#define HAL_TIMEx_DMACommutationCplt TIMEx_DMACommutationCplt -#if defined(STM32H7) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) -#define HAL_TIM_SlaveConfigSynchronization HAL_TIM_SlaveConfigSynchro -#define HAL_TIM_SlaveConfigSynchronization_IT HAL_TIM_SlaveConfigSynchro_IT -#define HAL_TIMEx_CommutationCallback HAL_TIMEx_CommutCallback -#define HAL_TIMEx_ConfigCommutationEvent HAL_TIMEx_ConfigCommutEvent -#define HAL_TIMEx_ConfigCommutationEvent_IT HAL_TIMEx_ConfigCommutEvent_IT -#define HAL_TIMEx_ConfigCommutationEvent_DMA HAL_TIMEx_ConfigCommutEvent_DMA -#endif /* STM32H7 || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 */ -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Functions HAL UART Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Functions HAL LTDC Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_LTDC_LineEvenCallback HAL_LTDC_LineEventCallback -#define HAL_LTDC_Relaod HAL_LTDC_Reload -#define HAL_LTDC_StructInitFromVideoConfig HAL_LTDCEx_StructInitFromVideoConfig -#define HAL_LTDC_StructInitFromAdaptedCommandConfig HAL_LTDCEx_StructInitFromAdaptedCommandConfig -/** - * @} - */ - - -/** @defgroup HAL_PPP_Aliased_Functions HAL PPP Aliased Functions maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported macros ------------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Macros HAL CRYP Aliased Macros maintained for legacy purpose - * @{ - */ -#define AES_IT_CC CRYP_IT_CC -#define AES_IT_ERR CRYP_IT_ERR -#define AES_FLAG_CCF CRYP_FLAG_CCF -/** - * @} - */ - -/** @defgroup HAL_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_GET_BOOT_MODE __HAL_SYSCFG_GET_BOOT_MODE -#define __HAL_REMAPMEMORY_FLASH __HAL_SYSCFG_REMAPMEMORY_FLASH -#define __HAL_REMAPMEMORY_SYSTEMFLASH __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH -#define __HAL_REMAPMEMORY_SRAM __HAL_SYSCFG_REMAPMEMORY_SRAM -#define __HAL_REMAPMEMORY_FMC __HAL_SYSCFG_REMAPMEMORY_FMC -#define __HAL_REMAPMEMORY_FMC_SDRAM __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM -#define __HAL_REMAPMEMORY_FSMC __HAL_SYSCFG_REMAPMEMORY_FSMC -#define __HAL_REMAPMEMORY_QUADSPI __HAL_SYSCFG_REMAPMEMORY_QUADSPI -#define __HAL_FMC_BANK __HAL_SYSCFG_FMC_BANK -#define __HAL_GET_FLAG __HAL_SYSCFG_GET_FLAG -#define __HAL_CLEAR_FLAG __HAL_SYSCFG_CLEAR_FLAG -#define __HAL_VREFINT_OUT_ENABLE __HAL_SYSCFG_VREFINT_OUT_ENABLE -#define __HAL_VREFINT_OUT_DISABLE __HAL_SYSCFG_VREFINT_OUT_DISABLE -#define __HAL_SYSCFG_SRAM2_WRP_ENABLE __HAL_SYSCFG_SRAM2_WRP_0_31_ENABLE - -#define SYSCFG_FLAG_VREF_READY SYSCFG_FLAG_VREFINT_READY -#define SYSCFG_FLAG_RC48 RCC_FLAG_HSI48 -#define IS_SYSCFG_FASTMODEPLUS_CONFIG IS_I2C_FASTMODEPLUS -#define UFB_MODE_BitNumber UFB_MODE_BIT_NUMBER -#define CMP_PD_BitNumber CMP_PD_BIT_NUMBER - -/** - * @} - */ - - -/** @defgroup HAL_ADC_Aliased_Macros HAL ADC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __ADC_ENABLE __HAL_ADC_ENABLE -#define __ADC_DISABLE __HAL_ADC_DISABLE -#define __HAL_ADC_ENABLING_CONDITIONS ADC_ENABLING_CONDITIONS -#define __HAL_ADC_DISABLING_CONDITIONS ADC_DISABLING_CONDITIONS -#define __HAL_ADC_IS_ENABLED ADC_IS_ENABLE -#define __ADC_IS_ENABLED ADC_IS_ENABLE -#define __HAL_ADC_IS_SOFTWARE_START_REGULAR ADC_IS_SOFTWARE_START_REGULAR -#define __HAL_ADC_IS_SOFTWARE_START_INJECTED ADC_IS_SOFTWARE_START_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR ADC_IS_CONVERSION_ONGOING_REGULAR -#define __HAL_ADC_IS_CONVERSION_ONGOING_INJECTED ADC_IS_CONVERSION_ONGOING_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING ADC_IS_CONVERSION_ONGOING -#define __HAL_ADC_CLEAR_ERRORCODE ADC_CLEAR_ERRORCODE - -#define __HAL_ADC_GET_RESOLUTION ADC_GET_RESOLUTION -#define __HAL_ADC_JSQR_RK ADC_JSQR_RK -#define __HAL_ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_SHIFT -#define __HAL_ADC_CFGR_AWD23CR ADC_CFGR_AWD23CR -#define __HAL_ADC_CFGR_INJECT_AUTO_CONVERSION ADC_CFGR_INJECT_AUTO_CONVERSION -#define __HAL_ADC_CFGR_INJECT_CONTEXT_QUEUE ADC_CFGR_INJECT_CONTEXT_QUEUE -#define __HAL_ADC_CFGR_INJECT_DISCCONTINUOUS ADC_CFGR_INJECT_DISCCONTINUOUS -#define __HAL_ADC_CFGR_REG_DISCCONTINUOUS ADC_CFGR_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR_DISCONTINUOUS_NUM ADC_CFGR_DISCONTINUOUS_NUM -#define __HAL_ADC_CFGR_AUTOWAIT ADC_CFGR_AUTOWAIT -#define __HAL_ADC_CFGR_CONTINUOUS ADC_CFGR_CONTINUOUS -#define __HAL_ADC_CFGR_OVERRUN ADC_CFGR_OVERRUN -#define __HAL_ADC_CFGR_DMACONTREQ ADC_CFGR_DMACONTREQ -#define __HAL_ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_SET -#define __HAL_ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_SET -#define __HAL_ADC_OFR_CHANNEL ADC_OFR_CHANNEL -#define __HAL_ADC_DIFSEL_CHANNEL ADC_DIFSEL_CHANNEL -#define __HAL_ADC_CALFACT_DIFF_SET ADC_CALFACT_DIFF_SET -#define __HAL_ADC_CALFACT_DIFF_GET ADC_CALFACT_DIFF_GET -#define __HAL_ADC_TRX_HIGHTHRESHOLD ADC_TRX_HIGHTHRESHOLD - -#define __HAL_ADC_OFFSET_SHIFT_RESOLUTION ADC_OFFSET_SHIFT_RESOLUTION -#define __HAL_ADC_AWD1THRESHOLD_SHIFT_RESOLUTION ADC_AWD1THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_AWD23THRESHOLD_SHIFT_RESOLUTION ADC_AWD23THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_COMMON_REGISTER ADC_COMMON_REGISTER -#define __HAL_ADC_COMMON_CCR_MULTI ADC_COMMON_CCR_MULTI -#define __HAL_ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __HAL_ADC_NONMULTIMODE_OR_MULTIMODEMASTER ADC_NONMULTIMODE_OR_MULTIMODEMASTER -#define __HAL_ADC_COMMON_ADC_OTHER ADC_COMMON_ADC_OTHER -#define __HAL_ADC_MULTI_SLAVE ADC_MULTI_SLAVE - -#define __HAL_ADC_SQR1_L ADC_SQR1_L_SHIFT -#define __HAL_ADC_JSQR_JL ADC_JSQR_JL_SHIFT -#define __HAL_ADC_JSQR_RK_JL ADC_JSQR_RK_JL -#define __HAL_ADC_CR1_DISCONTINUOUS_NUM ADC_CR1_DISCONTINUOUS_NUM -#define __HAL_ADC_CR1_SCAN ADC_CR1_SCAN_SET -#define __HAL_ADC_CONVCYCLES_MAX_RANGE ADC_CONVCYCLES_MAX_RANGE -#define __HAL_ADC_CLOCK_PRESCALER_RANGE ADC_CLOCK_PRESCALER_RANGE -#define __HAL_ADC_GET_CLOCK_PRESCALER ADC_GET_CLOCK_PRESCALER - -#define __HAL_ADC_SQR1 ADC_SQR1 -#define __HAL_ADC_SMPR1 ADC_SMPR1 -#define __HAL_ADC_SMPR2 ADC_SMPR2 -#define __HAL_ADC_SQR3_RK ADC_SQR3_RK -#define __HAL_ADC_SQR2_RK ADC_SQR2_RK -#define __HAL_ADC_SQR1_RK ADC_SQR1_RK -#define __HAL_ADC_CR2_CONTINUOUS ADC_CR2_CONTINUOUS -#define __HAL_ADC_CR1_DISCONTINUOUS ADC_CR1_DISCONTINUOUS -#define __HAL_ADC_CR1_SCANCONV ADC_CR1_SCANCONV -#define __HAL_ADC_CR2_EOCSelection ADC_CR2_EOCSelection -#define __HAL_ADC_CR2_DMAContReq ADC_CR2_DMAContReq -#define __HAL_ADC_JSQR ADC_JSQR - -#define __HAL_ADC_CHSELR_CHANNEL ADC_CHSELR_CHANNEL -#define __HAL_ADC_CFGR1_REG_DISCCONTINUOUS ADC_CFGR1_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR1_AUTOOFF ADC_CFGR1_AUTOOFF -#define __HAL_ADC_CFGR1_AUTOWAIT ADC_CFGR1_AUTOWAIT -#define __HAL_ADC_CFGR1_CONTINUOUS ADC_CFGR1_CONTINUOUS -#define __HAL_ADC_CFGR1_OVERRUN ADC_CFGR1_OVERRUN -#define __HAL_ADC_CFGR1_SCANDIR ADC_CFGR1_SCANDIR -#define __HAL_ADC_CFGR1_DMACONTREQ ADC_CFGR1_DMACONTREQ - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_DHR12R1_ALIGNEMENT DAC_DHR12R1_ALIGNMENT -#define __HAL_DHR12R2_ALIGNEMENT DAC_DHR12R2_ALIGNMENT -#define __HAL_DHR12RD_ALIGNEMENT DAC_DHR12RD_ALIGNMENT -#define IS_DAC_GENERATE_WAVE IS_DAC_WAVE - -/** - * @} - */ - -/** @defgroup HAL_DBGMCU_Aliased_Macros HAL DBGMCU Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_FREEZE_TIM1_DBGMCU __HAL_DBGMCU_FREEZE_TIM1 -#define __HAL_UNFREEZE_TIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM1 -#define __HAL_FREEZE_TIM2_DBGMCU __HAL_DBGMCU_FREEZE_TIM2 -#define __HAL_UNFREEZE_TIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM2 -#define __HAL_FREEZE_TIM3_DBGMCU __HAL_DBGMCU_FREEZE_TIM3 -#define __HAL_UNFREEZE_TIM3_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM3 -#define __HAL_FREEZE_TIM4_DBGMCU __HAL_DBGMCU_FREEZE_TIM4 -#define __HAL_UNFREEZE_TIM4_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM4 -#define __HAL_FREEZE_TIM5_DBGMCU __HAL_DBGMCU_FREEZE_TIM5 -#define __HAL_UNFREEZE_TIM5_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM5 -#define __HAL_FREEZE_TIM6_DBGMCU __HAL_DBGMCU_FREEZE_TIM6 -#define __HAL_UNFREEZE_TIM6_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM6 -#define __HAL_FREEZE_TIM7_DBGMCU __HAL_DBGMCU_FREEZE_TIM7 -#define __HAL_UNFREEZE_TIM7_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM7 -#define __HAL_FREEZE_TIM8_DBGMCU __HAL_DBGMCU_FREEZE_TIM8 -#define __HAL_UNFREEZE_TIM8_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM8 - -#define __HAL_FREEZE_TIM9_DBGMCU __HAL_DBGMCU_FREEZE_TIM9 -#define __HAL_UNFREEZE_TIM9_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM9 -#define __HAL_FREEZE_TIM10_DBGMCU __HAL_DBGMCU_FREEZE_TIM10 -#define __HAL_UNFREEZE_TIM10_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM10 -#define __HAL_FREEZE_TIM11_DBGMCU __HAL_DBGMCU_FREEZE_TIM11 -#define __HAL_UNFREEZE_TIM11_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM11 -#define __HAL_FREEZE_TIM12_DBGMCU __HAL_DBGMCU_FREEZE_TIM12 -#define __HAL_UNFREEZE_TIM12_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM12 -#define __HAL_FREEZE_TIM13_DBGMCU __HAL_DBGMCU_FREEZE_TIM13 -#define __HAL_UNFREEZE_TIM13_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM13 -#define __HAL_FREEZE_TIM14_DBGMCU __HAL_DBGMCU_FREEZE_TIM14 -#define __HAL_UNFREEZE_TIM14_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM14 -#define __HAL_FREEZE_CAN2_DBGMCU __HAL_DBGMCU_FREEZE_CAN2 -#define __HAL_UNFREEZE_CAN2_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN2 - - -#define __HAL_FREEZE_TIM15_DBGMCU __HAL_DBGMCU_FREEZE_TIM15 -#define __HAL_UNFREEZE_TIM15_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM15 -#define __HAL_FREEZE_TIM16_DBGMCU __HAL_DBGMCU_FREEZE_TIM16 -#define __HAL_UNFREEZE_TIM16_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM16 -#define __HAL_FREEZE_TIM17_DBGMCU __HAL_DBGMCU_FREEZE_TIM17 -#define __HAL_UNFREEZE_TIM17_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM17 -#define __HAL_FREEZE_RTC_DBGMCU __HAL_DBGMCU_FREEZE_RTC -#define __HAL_UNFREEZE_RTC_DBGMCU __HAL_DBGMCU_UNFREEZE_RTC -#if defined(STM32H7) -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG1 -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UnFreeze_WWDG1 -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG1 -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UnFreeze_IWDG1 -#else -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_WWDG -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_IWDG -#endif /* STM32H7 */ -#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT -#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT -#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT -#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT -#define __HAL_FREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT -#define __HAL_UNFREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT -#define __HAL_FREEZE_CAN1_DBGMCU __HAL_DBGMCU_FREEZE_CAN1 -#define __HAL_UNFREEZE_CAN1_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN1 -#define __HAL_FREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM1 -#define __HAL_UNFREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM1 -#define __HAL_FREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM2 -#define __HAL_UNFREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM2 - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Macros HAL COMP Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32F3) -#define COMP_START __HAL_COMP_ENABLE -#define COMP_STOP __HAL_COMP_DISABLE -#define COMP_LOCK __HAL_COMP_LOCK - -#if defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F302xE) || defined(STM32F302xC) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP7_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP7_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F373xC) ||defined(STM32F378xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -# endif -#else -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -#endif - -#define __HAL_COMP_GET_EXTI_LINE COMP_GET_EXTI_LINE - -#if defined(STM32L0) || defined(STM32L4) -/* Note: On these STM32 families, the only argument of this macro */ -/* is COMP_FLAG_LOCK. */ -/* This macro is replaced by __HAL_COMP_IS_LOCKED with only HAL handle */ -/* argument. */ -#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (__HAL_COMP_IS_LOCKED(__HANDLE__)) -#endif -/** - * @} - */ - -#if defined(STM32L0) || defined(STM32L4) -/** @defgroup HAL_COMP_Aliased_Functions HAL COMP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_COMP_Start_IT HAL_COMP_Start /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -#define HAL_COMP_Stop_IT HAL_COMP_Stop /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -/** - * @} - */ -#endif - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_WAVE_NONE) || \ - ((WAVE) == DAC_WAVE_NOISE)|| \ - ((WAVE) == DAC_WAVE_TRIANGLE)) - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Macros HAL FLASH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_WRPAREA IS_OB_WRPAREA -#define IS_TYPEPROGRAM IS_FLASH_TYPEPROGRAM -#define IS_TYPEPROGRAMFLASH IS_FLASH_TYPEPROGRAM -#define IS_TYPEERASE IS_FLASH_TYPEERASE -#define IS_NBSECTORS IS_FLASH_NBSECTORS -#define IS_OB_WDG_SOURCE IS_OB_IWDG_SOURCE - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Macros HAL I2C Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_I2C_RESET_CR2 I2C_RESET_CR2 -#define __HAL_I2C_GENERATE_START I2C_GENERATE_START -#if defined(STM32F1) -#define __HAL_I2C_FREQ_RANGE I2C_FREQRANGE -#else -#define __HAL_I2C_FREQ_RANGE I2C_FREQ_RANGE -#endif /* STM32F1 */ -#define __HAL_I2C_RISE_TIME I2C_RISE_TIME -#define __HAL_I2C_SPEED_STANDARD I2C_SPEED_STANDARD -#define __HAL_I2C_SPEED_FAST I2C_SPEED_FAST -#define __HAL_I2C_SPEED I2C_SPEED -#define __HAL_I2C_7BIT_ADD_WRITE I2C_7BIT_ADD_WRITE -#define __HAL_I2C_7BIT_ADD_READ I2C_7BIT_ADD_READ -#define __HAL_I2C_10BIT_ADDRESS I2C_10BIT_ADDRESS -#define __HAL_I2C_10BIT_HEADER_WRITE I2C_10BIT_HEADER_WRITE -#define __HAL_I2C_10BIT_HEADER_READ I2C_10BIT_HEADER_READ -#define __HAL_I2C_MEM_ADD_MSB I2C_MEM_ADD_MSB -#define __HAL_I2C_MEM_ADD_LSB I2C_MEM_ADD_LSB -#define __HAL_I2C_FREQRANGE I2C_FREQRANGE -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Macros HAL I2S Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_I2S_INSTANCE IS_I2S_ALL_INSTANCE -#define IS_I2S_INSTANCE_EXT IS_I2S_ALL_INSTANCE_EXT - -#if defined(STM32H7) -#define __HAL_I2S_CLEAR_FREFLAG __HAL_I2S_CLEAR_TIFREFLAG -#endif - -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Macros HAL IRDA Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __IRDA_DISABLE __HAL_IRDA_DISABLE -#define __IRDA_ENABLE __HAL_IRDA_ENABLE - -#define __HAL_IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __HAL_IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION -#define __IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION - -#define IS_IRDA_ONEBIT_SAMPLE IS_IRDA_ONE_BIT_SAMPLE - - -/** - * @} - */ - - -/** @defgroup HAL_IWDG_Aliased_Macros HAL IWDG Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_IWDG_ENABLE_WRITE_ACCESS IWDG_ENABLE_WRITE_ACCESS -#define __HAL_IWDG_DISABLE_WRITE_ACCESS IWDG_DISABLE_WRITE_ACCESS -/** - * @} - */ - - -/** @defgroup HAL_LPTIM_Aliased_Macros HAL LPTIM Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_LPTIM_ENABLE_INTERRUPT __HAL_LPTIM_ENABLE_IT -#define __HAL_LPTIM_DISABLE_INTERRUPT __HAL_LPTIM_DISABLE_IT -#define __HAL_LPTIM_GET_ITSTATUS __HAL_LPTIM_GET_IT_SOURCE - -/** - * @} - */ - - -/** @defgroup HAL_OPAMP_Aliased_Macros HAL OPAMP Aliased Macros maintained for legacy purpose - * @{ - */ -#define __OPAMP_CSR_OPAXPD OPAMP_CSR_OPAXPD -#define __OPAMP_CSR_S3SELX OPAMP_CSR_S3SELX -#define __OPAMP_CSR_S4SELX OPAMP_CSR_S4SELX -#define __OPAMP_CSR_S5SELX OPAMP_CSR_S5SELX -#define __OPAMP_CSR_S6SELX OPAMP_CSR_S6SELX -#define __OPAMP_CSR_OPAXCAL_L OPAMP_CSR_OPAXCAL_L -#define __OPAMP_CSR_OPAXCAL_H OPAMP_CSR_OPAXCAL_H -#define __OPAMP_CSR_OPAXLPM OPAMP_CSR_OPAXLPM -#define __OPAMP_CSR_ALL_SWITCHES OPAMP_CSR_ALL_SWITCHES -#define __OPAMP_CSR_ANAWSELX OPAMP_CSR_ANAWSELX -#define __OPAMP_CSR_OPAXCALOUT OPAMP_CSR_OPAXCALOUT -#define __OPAMP_OFFSET_TRIM_BITSPOSITION OPAMP_OFFSET_TRIM_BITSPOSITION -#define __OPAMP_OFFSET_TRIM_SET OPAMP_OFFSET_TRIM_SET - -/** - * @} - */ - - -/** @defgroup HAL_PWR_Aliased_Macros HAL PWR Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_PVD_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PVD_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PVM_EVENT_DISABLE __HAL_PWR_PVM_EVENT_DISABLE -#define __HAL_PVM_EVENT_ENABLE __HAL_PWR_PVM_EVENT_ENABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_ENABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_ENABLE -#define __HAL_PWR_INTERNALWAKEUP_DISABLE HAL_PWREx_DisableInternalWakeUpLine -#define __HAL_PWR_INTERNALWAKEUP_ENABLE HAL_PWREx_EnableInternalWakeUpLine -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_DISABLE HAL_PWREx_DisablePullUpPullDownConfig -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_ENABLE HAL_PWREx_EnablePullUpPullDownConfig -#define __HAL_PWR_PVD_EXTI_CLEAR_EGDE_TRIGGER() do { __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); } while(0) -#define __HAL_PWR_PVD_EXTI_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PWR_PVD_EXTI_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_RISING_EDGE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVM_DISABLE() do { HAL_PWREx_DisablePVM1();HAL_PWREx_DisablePVM2();HAL_PWREx_DisablePVM3();HAL_PWREx_DisablePVM4(); } while(0) -#define __HAL_PWR_PVM_ENABLE() do { HAL_PWREx_EnablePVM1();HAL_PWREx_EnablePVM2();HAL_PWREx_EnablePVM3();HAL_PWREx_EnablePVM4(); } while(0) -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_DISABLE HAL_PWREx_DisableSRAM2ContentRetention -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_ENABLE HAL_PWREx_EnableSRAM2ContentRetention -#define __HAL_PWR_VDDIO2_DISABLE HAL_PWREx_DisableVddIO2 -#define __HAL_PWR_VDDIO2_ENABLE HAL_PWREx_EnableVddIO2 -#define __HAL_PWR_VDDIO2_EXTI_CLEAR_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_VDDIO2_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_VDDUSB_DISABLE HAL_PWREx_DisableVddUSB -#define __HAL_PWR_VDDUSB_ENABLE HAL_PWREx_EnableVddUSB - -#if defined (STM32F4) -#define __HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_ENABLE_IT() -#define __HAL_PVD_EXTI_DISABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_DISABLE_IT() -#define __HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GET_FLAG() -#define __HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_CLEAR_FLAG() -#define __HAL_PVD_EXTI_GENERATE_SWIT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GENERATE_SWIT() -#else -#define __HAL_PVD_EXTI_CLEAR_FLAG __HAL_PWR_PVD_EXTI_CLEAR_FLAG -#define __HAL_PVD_EXTI_DISABLE_IT __HAL_PWR_PVD_EXTI_DISABLE_IT -#define __HAL_PVD_EXTI_ENABLE_IT __HAL_PWR_PVD_EXTI_ENABLE_IT -#define __HAL_PVD_EXTI_GENERATE_SWIT __HAL_PWR_PVD_EXTI_GENERATE_SWIT -#define __HAL_PVD_EXTI_GET_FLAG __HAL_PWR_PVD_EXTI_GET_FLAG -#endif /* STM32F4 */ -/** - * @} - */ - - -/** @defgroup HAL_RCC_Aliased HAL RCC Aliased maintained for legacy purpose - * @{ - */ - -#define RCC_StopWakeUpClock_MSI RCC_STOP_WAKEUPCLOCK_MSI -#define RCC_StopWakeUpClock_HSI RCC_STOP_WAKEUPCLOCK_HSI - -#define HAL_RCC_CCSCallback HAL_RCC_CSSCallback -#define HAL_RC48_EnableBuffer_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_RCCEx_EnableHSI48_VREFINT() : HAL_RCCEx_DisableHSI48_VREFINT()) - -#define __ADC_CLK_DISABLE __HAL_RCC_ADC_CLK_DISABLE -#define __ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE -#define __ADC_CLK_SLEEP_DISABLE __HAL_RCC_ADC_CLK_SLEEP_DISABLE -#define __ADC_CLK_SLEEP_ENABLE __HAL_RCC_ADC_CLK_SLEEP_ENABLE -#define __ADC_FORCE_RESET __HAL_RCC_ADC_FORCE_RESET -#define __ADC_RELEASE_RESET __HAL_RCC_ADC_RELEASE_RESET -#define __ADC1_CLK_DISABLE __HAL_RCC_ADC1_CLK_DISABLE -#define __ADC1_CLK_ENABLE __HAL_RCC_ADC1_CLK_ENABLE -#define __ADC1_FORCE_RESET __HAL_RCC_ADC1_FORCE_RESET -#define __ADC1_RELEASE_RESET __HAL_RCC_ADC1_RELEASE_RESET -#define __ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC1_CLK_SLEEP_ENABLE -#define __ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC1_CLK_SLEEP_DISABLE -#define __ADC2_CLK_DISABLE __HAL_RCC_ADC2_CLK_DISABLE -#define __ADC2_CLK_ENABLE __HAL_RCC_ADC2_CLK_ENABLE -#define __ADC2_FORCE_RESET __HAL_RCC_ADC2_FORCE_RESET -#define __ADC2_RELEASE_RESET __HAL_RCC_ADC2_RELEASE_RESET -#define __ADC3_CLK_DISABLE __HAL_RCC_ADC3_CLK_DISABLE -#define __ADC3_CLK_ENABLE __HAL_RCC_ADC3_CLK_ENABLE -#define __ADC3_FORCE_RESET __HAL_RCC_ADC3_FORCE_RESET -#define __ADC3_RELEASE_RESET __HAL_RCC_ADC3_RELEASE_RESET -#define __AES_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __AES_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __AES_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __AES_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __AES_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __AES_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#define __CRYP_CLK_SLEEP_ENABLE __HAL_RCC_CRYP_CLK_SLEEP_ENABLE -#define __CRYP_CLK_SLEEP_DISABLE __HAL_RCC_CRYP_CLK_SLEEP_DISABLE -#define __CRYP_CLK_ENABLE __HAL_RCC_CRYP_CLK_ENABLE -#define __CRYP_CLK_DISABLE __HAL_RCC_CRYP_CLK_DISABLE -#define __CRYP_FORCE_RESET __HAL_RCC_CRYP_FORCE_RESET -#define __CRYP_RELEASE_RESET __HAL_RCC_CRYP_RELEASE_RESET -#define __AFIO_CLK_DISABLE __HAL_RCC_AFIO_CLK_DISABLE -#define __AFIO_CLK_ENABLE __HAL_RCC_AFIO_CLK_ENABLE -#define __AFIO_FORCE_RESET __HAL_RCC_AFIO_FORCE_RESET -#define __AFIO_RELEASE_RESET __HAL_RCC_AFIO_RELEASE_RESET -#define __AHB_FORCE_RESET __HAL_RCC_AHB_FORCE_RESET -#define __AHB_RELEASE_RESET __HAL_RCC_AHB_RELEASE_RESET -#define __AHB1_FORCE_RESET __HAL_RCC_AHB1_FORCE_RESET -#define __AHB1_RELEASE_RESET __HAL_RCC_AHB1_RELEASE_RESET -#define __AHB2_FORCE_RESET __HAL_RCC_AHB2_FORCE_RESET -#define __AHB2_RELEASE_RESET __HAL_RCC_AHB2_RELEASE_RESET -#define __AHB3_FORCE_RESET __HAL_RCC_AHB3_FORCE_RESET -#define __AHB3_RELEASE_RESET __HAL_RCC_AHB3_RELEASE_RESET -#define __APB1_FORCE_RESET __HAL_RCC_APB1_FORCE_RESET -#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET -#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET -#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET -#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE -#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE -#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET -#define __BKP_RELEASE_RESET __HAL_RCC_BKP_RELEASE_RESET -#define __CAN1_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN1_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN1_CLK_SLEEP_DISABLE __HAL_RCC_CAN1_CLK_SLEEP_DISABLE -#define __CAN1_CLK_SLEEP_ENABLE __HAL_RCC_CAN1_CLK_SLEEP_ENABLE -#define __CAN1_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN1_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN2_CLK_DISABLE __HAL_RCC_CAN2_CLK_DISABLE -#define __CAN2_CLK_ENABLE __HAL_RCC_CAN2_CLK_ENABLE -#define __CAN2_FORCE_RESET __HAL_RCC_CAN2_FORCE_RESET -#define __CAN2_RELEASE_RESET __HAL_RCC_CAN2_RELEASE_RESET -#define __CEC_CLK_DISABLE __HAL_RCC_CEC_CLK_DISABLE -#define __CEC_CLK_ENABLE __HAL_RCC_CEC_CLK_ENABLE -#define __COMP_CLK_DISABLE __HAL_RCC_COMP_CLK_DISABLE -#define __COMP_CLK_ENABLE __HAL_RCC_COMP_CLK_ENABLE -#define __COMP_FORCE_RESET __HAL_RCC_COMP_FORCE_RESET -#define __COMP_RELEASE_RESET __HAL_RCC_COMP_RELEASE_RESET -#define __COMP_CLK_SLEEP_ENABLE __HAL_RCC_COMP_CLK_SLEEP_ENABLE -#define __COMP_CLK_SLEEP_DISABLE __HAL_RCC_COMP_CLK_SLEEP_DISABLE -#define __CEC_FORCE_RESET __HAL_RCC_CEC_FORCE_RESET -#define __CEC_RELEASE_RESET __HAL_RCC_CEC_RELEASE_RESET -#define __CRC_CLK_DISABLE __HAL_RCC_CRC_CLK_DISABLE -#define __CRC_CLK_ENABLE __HAL_RCC_CRC_CLK_ENABLE -#define __CRC_CLK_SLEEP_DISABLE __HAL_RCC_CRC_CLK_SLEEP_DISABLE -#define __CRC_CLK_SLEEP_ENABLE __HAL_RCC_CRC_CLK_SLEEP_ENABLE -#define __CRC_FORCE_RESET __HAL_RCC_CRC_FORCE_RESET -#define __CRC_RELEASE_RESET __HAL_RCC_CRC_RELEASE_RESET -#define __DAC_CLK_DISABLE __HAL_RCC_DAC_CLK_DISABLE -#define __DAC_CLK_ENABLE __HAL_RCC_DAC_CLK_ENABLE -#define __DAC_FORCE_RESET __HAL_RCC_DAC_FORCE_RESET -#define __DAC_RELEASE_RESET __HAL_RCC_DAC_RELEASE_RESET -#define __DAC1_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE -#define __DAC1_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE -#define __DAC1_CLK_SLEEP_DISABLE __HAL_RCC_DAC1_CLK_SLEEP_DISABLE -#define __DAC1_CLK_SLEEP_ENABLE __HAL_RCC_DAC1_CLK_SLEEP_ENABLE -#define __DAC1_FORCE_RESET __HAL_RCC_DAC1_FORCE_RESET -#define __DAC1_RELEASE_RESET __HAL_RCC_DAC1_RELEASE_RESET -#define __DBGMCU_CLK_ENABLE __HAL_RCC_DBGMCU_CLK_ENABLE -#define __DBGMCU_CLK_DISABLE __HAL_RCC_DBGMCU_CLK_DISABLE -#define __DBGMCU_FORCE_RESET __HAL_RCC_DBGMCU_FORCE_RESET -#define __DBGMCU_RELEASE_RESET __HAL_RCC_DBGMCU_RELEASE_RESET -#define __DFSDM_CLK_DISABLE __HAL_RCC_DFSDM_CLK_DISABLE -#define __DFSDM_CLK_ENABLE __HAL_RCC_DFSDM_CLK_ENABLE -#define __DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE -#define __DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE -#define __DFSDM_FORCE_RESET __HAL_RCC_DFSDM_FORCE_RESET -#define __DFSDM_RELEASE_RESET __HAL_RCC_DFSDM_RELEASE_RESET -#define __DMA1_CLK_DISABLE __HAL_RCC_DMA1_CLK_DISABLE -#define __DMA1_CLK_ENABLE __HAL_RCC_DMA1_CLK_ENABLE -#define __DMA1_CLK_SLEEP_DISABLE __HAL_RCC_DMA1_CLK_SLEEP_DISABLE -#define __DMA1_CLK_SLEEP_ENABLE __HAL_RCC_DMA1_CLK_SLEEP_ENABLE -#define __DMA1_FORCE_RESET __HAL_RCC_DMA1_FORCE_RESET -#define __DMA1_RELEASE_RESET __HAL_RCC_DMA1_RELEASE_RESET -#define __DMA2_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE -#define __DMA2_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE -#define __DMA2_CLK_SLEEP_DISABLE __HAL_RCC_DMA2_CLK_SLEEP_DISABLE -#define __DMA2_CLK_SLEEP_ENABLE __HAL_RCC_DMA2_CLK_SLEEP_ENABLE -#define __DMA2_FORCE_RESET __HAL_RCC_DMA2_FORCE_RESET -#define __DMA2_RELEASE_RESET __HAL_RCC_DMA2_RELEASE_RESET -#define __ETHMAC_CLK_DISABLE __HAL_RCC_ETHMAC_CLK_DISABLE -#define __ETHMAC_CLK_ENABLE __HAL_RCC_ETHMAC_CLK_ENABLE -#define __ETHMAC_FORCE_RESET __HAL_RCC_ETHMAC_FORCE_RESET -#define __ETHMAC_RELEASE_RESET __HAL_RCC_ETHMAC_RELEASE_RESET -#define __ETHMACRX_CLK_DISABLE __HAL_RCC_ETHMACRX_CLK_DISABLE -#define __ETHMACRX_CLK_ENABLE __HAL_RCC_ETHMACRX_CLK_ENABLE -#define __ETHMACTX_CLK_DISABLE __HAL_RCC_ETHMACTX_CLK_DISABLE -#define __ETHMACTX_CLK_ENABLE __HAL_RCC_ETHMACTX_CLK_ENABLE -#define __FIREWALL_CLK_DISABLE __HAL_RCC_FIREWALL_CLK_DISABLE -#define __FIREWALL_CLK_ENABLE __HAL_RCC_FIREWALL_CLK_ENABLE -#define __FLASH_CLK_DISABLE __HAL_RCC_FLASH_CLK_DISABLE -#define __FLASH_CLK_ENABLE __HAL_RCC_FLASH_CLK_ENABLE -#define __FLASH_CLK_SLEEP_DISABLE __HAL_RCC_FLASH_CLK_SLEEP_DISABLE -#define __FLASH_CLK_SLEEP_ENABLE __HAL_RCC_FLASH_CLK_SLEEP_ENABLE -#define __FLASH_FORCE_RESET __HAL_RCC_FLASH_FORCE_RESET -#define __FLASH_RELEASE_RESET __HAL_RCC_FLASH_RELEASE_RESET -#define __FLITF_CLK_DISABLE __HAL_RCC_FLITF_CLK_DISABLE -#define __FLITF_CLK_ENABLE __HAL_RCC_FLITF_CLK_ENABLE -#define __FLITF_FORCE_RESET __HAL_RCC_FLITF_FORCE_RESET -#define __FLITF_RELEASE_RESET __HAL_RCC_FLITF_RELEASE_RESET -#define __FLITF_CLK_SLEEP_ENABLE __HAL_RCC_FLITF_CLK_SLEEP_ENABLE -#define __FLITF_CLK_SLEEP_DISABLE __HAL_RCC_FLITF_CLK_SLEEP_DISABLE -#define __FMC_CLK_DISABLE __HAL_RCC_FMC_CLK_DISABLE -#define __FMC_CLK_ENABLE __HAL_RCC_FMC_CLK_ENABLE -#define __FMC_CLK_SLEEP_DISABLE __HAL_RCC_FMC_CLK_SLEEP_DISABLE -#define __FMC_CLK_SLEEP_ENABLE __HAL_RCC_FMC_CLK_SLEEP_ENABLE -#define __FMC_FORCE_RESET __HAL_RCC_FMC_FORCE_RESET -#define __FMC_RELEASE_RESET __HAL_RCC_FMC_RELEASE_RESET -#define __FSMC_CLK_DISABLE __HAL_RCC_FSMC_CLK_DISABLE -#define __FSMC_CLK_ENABLE __HAL_RCC_FSMC_CLK_ENABLE -#define __GPIOA_CLK_DISABLE __HAL_RCC_GPIOA_CLK_DISABLE -#define __GPIOA_CLK_ENABLE __HAL_RCC_GPIOA_CLK_ENABLE -#define __GPIOA_CLK_SLEEP_DISABLE __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE -#define __GPIOA_CLK_SLEEP_ENABLE __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE -#define __GPIOA_FORCE_RESET __HAL_RCC_GPIOA_FORCE_RESET -#define __GPIOA_RELEASE_RESET __HAL_RCC_GPIOA_RELEASE_RESET -#define __GPIOB_CLK_DISABLE __HAL_RCC_GPIOB_CLK_DISABLE -#define __GPIOB_CLK_ENABLE __HAL_RCC_GPIOB_CLK_ENABLE -#define __GPIOB_CLK_SLEEP_DISABLE __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE -#define __GPIOB_CLK_SLEEP_ENABLE __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE -#define __GPIOB_FORCE_RESET __HAL_RCC_GPIOB_FORCE_RESET -#define __GPIOB_RELEASE_RESET __HAL_RCC_GPIOB_RELEASE_RESET -#define __GPIOC_CLK_DISABLE __HAL_RCC_GPIOC_CLK_DISABLE -#define __GPIOC_CLK_ENABLE __HAL_RCC_GPIOC_CLK_ENABLE -#define __GPIOC_CLK_SLEEP_DISABLE __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE -#define __GPIOC_CLK_SLEEP_ENABLE __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE -#define __GPIOC_FORCE_RESET __HAL_RCC_GPIOC_FORCE_RESET -#define __GPIOC_RELEASE_RESET __HAL_RCC_GPIOC_RELEASE_RESET -#define __GPIOD_CLK_DISABLE __HAL_RCC_GPIOD_CLK_DISABLE -#define __GPIOD_CLK_ENABLE __HAL_RCC_GPIOD_CLK_ENABLE -#define __GPIOD_CLK_SLEEP_DISABLE __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE -#define __GPIOD_CLK_SLEEP_ENABLE __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE -#define __GPIOD_FORCE_RESET __HAL_RCC_GPIOD_FORCE_RESET -#define __GPIOD_RELEASE_RESET __HAL_RCC_GPIOD_RELEASE_RESET -#define __GPIOE_CLK_DISABLE __HAL_RCC_GPIOE_CLK_DISABLE -#define __GPIOE_CLK_ENABLE __HAL_RCC_GPIOE_CLK_ENABLE -#define __GPIOE_CLK_SLEEP_DISABLE __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE -#define __GPIOE_CLK_SLEEP_ENABLE __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE -#define __GPIOE_FORCE_RESET __HAL_RCC_GPIOE_FORCE_RESET -#define __GPIOE_RELEASE_RESET __HAL_RCC_GPIOE_RELEASE_RESET -#define __GPIOF_CLK_DISABLE __HAL_RCC_GPIOF_CLK_DISABLE -#define __GPIOF_CLK_ENABLE __HAL_RCC_GPIOF_CLK_ENABLE -#define __GPIOF_CLK_SLEEP_DISABLE __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE -#define __GPIOF_CLK_SLEEP_ENABLE __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE -#define __GPIOF_FORCE_RESET __HAL_RCC_GPIOF_FORCE_RESET -#define __GPIOF_RELEASE_RESET __HAL_RCC_GPIOF_RELEASE_RESET -#define __GPIOG_CLK_DISABLE __HAL_RCC_GPIOG_CLK_DISABLE -#define __GPIOG_CLK_ENABLE __HAL_RCC_GPIOG_CLK_ENABLE -#define __GPIOG_CLK_SLEEP_DISABLE __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE -#define __GPIOG_CLK_SLEEP_ENABLE __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE -#define __GPIOG_FORCE_RESET __HAL_RCC_GPIOG_FORCE_RESET -#define __GPIOG_RELEASE_RESET __HAL_RCC_GPIOG_RELEASE_RESET -#define __GPIOH_CLK_DISABLE __HAL_RCC_GPIOH_CLK_DISABLE -#define __GPIOH_CLK_ENABLE __HAL_RCC_GPIOH_CLK_ENABLE -#define __GPIOH_CLK_SLEEP_DISABLE __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE -#define __GPIOH_CLK_SLEEP_ENABLE __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE -#define __GPIOH_FORCE_RESET __HAL_RCC_GPIOH_FORCE_RESET -#define __GPIOH_RELEASE_RESET __HAL_RCC_GPIOH_RELEASE_RESET -#define __I2C1_CLK_DISABLE __HAL_RCC_I2C1_CLK_DISABLE -#define __I2C1_CLK_ENABLE __HAL_RCC_I2C1_CLK_ENABLE -#define __I2C1_CLK_SLEEP_DISABLE __HAL_RCC_I2C1_CLK_SLEEP_DISABLE -#define __I2C1_CLK_SLEEP_ENABLE __HAL_RCC_I2C1_CLK_SLEEP_ENABLE -#define __I2C1_FORCE_RESET __HAL_RCC_I2C1_FORCE_RESET -#define __I2C1_RELEASE_RESET __HAL_RCC_I2C1_RELEASE_RESET -#define __I2C2_CLK_DISABLE __HAL_RCC_I2C2_CLK_DISABLE -#define __I2C2_CLK_ENABLE __HAL_RCC_I2C2_CLK_ENABLE -#define __I2C2_CLK_SLEEP_DISABLE __HAL_RCC_I2C2_CLK_SLEEP_DISABLE -#define __I2C2_CLK_SLEEP_ENABLE __HAL_RCC_I2C2_CLK_SLEEP_ENABLE -#define __I2C2_FORCE_RESET __HAL_RCC_I2C2_FORCE_RESET -#define __I2C2_RELEASE_RESET __HAL_RCC_I2C2_RELEASE_RESET -#define __I2C3_CLK_DISABLE __HAL_RCC_I2C3_CLK_DISABLE -#define __I2C3_CLK_ENABLE __HAL_RCC_I2C3_CLK_ENABLE -#define __I2C3_CLK_SLEEP_DISABLE __HAL_RCC_I2C3_CLK_SLEEP_DISABLE -#define __I2C3_CLK_SLEEP_ENABLE __HAL_RCC_I2C3_CLK_SLEEP_ENABLE -#define __I2C3_FORCE_RESET __HAL_RCC_I2C3_FORCE_RESET -#define __I2C3_RELEASE_RESET __HAL_RCC_I2C3_RELEASE_RESET -#define __LCD_CLK_DISABLE __HAL_RCC_LCD_CLK_DISABLE -#define __LCD_CLK_ENABLE __HAL_RCC_LCD_CLK_ENABLE -#define __LCD_CLK_SLEEP_DISABLE __HAL_RCC_LCD_CLK_SLEEP_DISABLE -#define __LCD_CLK_SLEEP_ENABLE __HAL_RCC_LCD_CLK_SLEEP_ENABLE -#define __LCD_FORCE_RESET __HAL_RCC_LCD_FORCE_RESET -#define __LCD_RELEASE_RESET __HAL_RCC_LCD_RELEASE_RESET -#define __LPTIM1_CLK_DISABLE __HAL_RCC_LPTIM1_CLK_DISABLE -#define __LPTIM1_CLK_ENABLE __HAL_RCC_LPTIM1_CLK_ENABLE -#define __LPTIM1_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE -#define __LPTIM1_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE -#define __LPTIM1_FORCE_RESET __HAL_RCC_LPTIM1_FORCE_RESET -#define __LPTIM1_RELEASE_RESET __HAL_RCC_LPTIM1_RELEASE_RESET -#define __LPTIM2_CLK_DISABLE __HAL_RCC_LPTIM2_CLK_DISABLE -#define __LPTIM2_CLK_ENABLE __HAL_RCC_LPTIM2_CLK_ENABLE -#define __LPTIM2_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM2_CLK_SLEEP_DISABLE -#define __LPTIM2_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM2_CLK_SLEEP_ENABLE -#define __LPTIM2_FORCE_RESET __HAL_RCC_LPTIM2_FORCE_RESET -#define __LPTIM2_RELEASE_RESET __HAL_RCC_LPTIM2_RELEASE_RESET -#define __LPUART1_CLK_DISABLE __HAL_RCC_LPUART1_CLK_DISABLE -#define __LPUART1_CLK_ENABLE __HAL_RCC_LPUART1_CLK_ENABLE -#define __LPUART1_CLK_SLEEP_DISABLE __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE -#define __LPUART1_CLK_SLEEP_ENABLE __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE -#define __LPUART1_FORCE_RESET __HAL_RCC_LPUART1_FORCE_RESET -#define __LPUART1_RELEASE_RESET __HAL_RCC_LPUART1_RELEASE_RESET -#define __OPAMP_CLK_DISABLE __HAL_RCC_OPAMP_CLK_DISABLE -#define __OPAMP_CLK_ENABLE __HAL_RCC_OPAMP_CLK_ENABLE -#define __OPAMP_CLK_SLEEP_DISABLE __HAL_RCC_OPAMP_CLK_SLEEP_DISABLE -#define __OPAMP_CLK_SLEEP_ENABLE __HAL_RCC_OPAMP_CLK_SLEEP_ENABLE -#define __OPAMP_FORCE_RESET __HAL_RCC_OPAMP_FORCE_RESET -#define __OPAMP_RELEASE_RESET __HAL_RCC_OPAMP_RELEASE_RESET -#define __OTGFS_CLK_DISABLE __HAL_RCC_OTGFS_CLK_DISABLE -#define __OTGFS_CLK_ENABLE __HAL_RCC_OTGFS_CLK_ENABLE -#define __OTGFS_CLK_SLEEP_DISABLE __HAL_RCC_OTGFS_CLK_SLEEP_DISABLE -#define __OTGFS_CLK_SLEEP_ENABLE __HAL_RCC_OTGFS_CLK_SLEEP_ENABLE -#define __OTGFS_FORCE_RESET __HAL_RCC_OTGFS_FORCE_RESET -#define __OTGFS_RELEASE_RESET __HAL_RCC_OTGFS_RELEASE_RESET -#define __PWR_CLK_DISABLE __HAL_RCC_PWR_CLK_DISABLE -#define __PWR_CLK_ENABLE __HAL_RCC_PWR_CLK_ENABLE -#define __PWR_CLK_SLEEP_DISABLE __HAL_RCC_PWR_CLK_SLEEP_DISABLE -#define __PWR_CLK_SLEEP_ENABLE __HAL_RCC_PWR_CLK_SLEEP_ENABLE -#define __PWR_FORCE_RESET __HAL_RCC_PWR_FORCE_RESET -#define __PWR_RELEASE_RESET __HAL_RCC_PWR_RELEASE_RESET -#define __QSPI_CLK_DISABLE __HAL_RCC_QSPI_CLK_DISABLE -#define __QSPI_CLK_ENABLE __HAL_RCC_QSPI_CLK_ENABLE -#define __QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QSPI_CLK_SLEEP_DISABLE -#define __QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QSPI_CLK_SLEEP_ENABLE -#define __QSPI_FORCE_RESET __HAL_RCC_QSPI_FORCE_RESET -#define __QSPI_RELEASE_RESET __HAL_RCC_QSPI_RELEASE_RESET - -#if defined(STM32WB) -#define __HAL_RCC_QSPI_CLK_DISABLE __HAL_RCC_QUADSPI_CLK_DISABLE -#define __HAL_RCC_QSPI_CLK_ENABLE __HAL_RCC_QUADSPI_CLK_ENABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QUADSPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QUADSPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_QSPI_FORCE_RESET __HAL_RCC_QUADSPI_FORCE_RESET -#define __HAL_RCC_QSPI_RELEASE_RESET __HAL_RCC_QUADSPI_RELEASE_RESET -#define __HAL_RCC_QSPI_IS_CLK_ENABLED __HAL_RCC_QUADSPI_IS_CLK_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_DISABLED __HAL_RCC_QUADSPI_IS_CLK_DISABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_DISABLED -#define QSPI_IRQHandler QUADSPI_IRQHandler -#endif /* __HAL_RCC_QUADSPI_CLK_ENABLE */ - -#define __RNG_CLK_DISABLE __HAL_RCC_RNG_CLK_DISABLE -#define __RNG_CLK_ENABLE __HAL_RCC_RNG_CLK_ENABLE -#define __RNG_CLK_SLEEP_DISABLE __HAL_RCC_RNG_CLK_SLEEP_DISABLE -#define __RNG_CLK_SLEEP_ENABLE __HAL_RCC_RNG_CLK_SLEEP_ENABLE -#define __RNG_FORCE_RESET __HAL_RCC_RNG_FORCE_RESET -#define __RNG_RELEASE_RESET __HAL_RCC_RNG_RELEASE_RESET -#define __SAI1_CLK_DISABLE __HAL_RCC_SAI1_CLK_DISABLE -#define __SAI1_CLK_ENABLE __HAL_RCC_SAI1_CLK_ENABLE -#define __SAI1_CLK_SLEEP_DISABLE __HAL_RCC_SAI1_CLK_SLEEP_DISABLE -#define __SAI1_CLK_SLEEP_ENABLE __HAL_RCC_SAI1_CLK_SLEEP_ENABLE -#define __SAI1_FORCE_RESET __HAL_RCC_SAI1_FORCE_RESET -#define __SAI1_RELEASE_RESET __HAL_RCC_SAI1_RELEASE_RESET -#define __SAI2_CLK_DISABLE __HAL_RCC_SAI2_CLK_DISABLE -#define __SAI2_CLK_ENABLE __HAL_RCC_SAI2_CLK_ENABLE -#define __SAI2_CLK_SLEEP_DISABLE __HAL_RCC_SAI2_CLK_SLEEP_DISABLE -#define __SAI2_CLK_SLEEP_ENABLE __HAL_RCC_SAI2_CLK_SLEEP_ENABLE -#define __SAI2_FORCE_RESET __HAL_RCC_SAI2_FORCE_RESET -#define __SAI2_RELEASE_RESET __HAL_RCC_SAI2_RELEASE_RESET -#define __SDIO_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __SDIO_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __SDMMC_CLK_DISABLE __HAL_RCC_SDMMC_CLK_DISABLE -#define __SDMMC_CLK_ENABLE __HAL_RCC_SDMMC_CLK_ENABLE -#define __SDMMC_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC_CLK_SLEEP_DISABLE -#define __SDMMC_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC_CLK_SLEEP_ENABLE -#define __SDMMC_FORCE_RESET __HAL_RCC_SDMMC_FORCE_RESET -#define __SDMMC_RELEASE_RESET __HAL_RCC_SDMMC_RELEASE_RESET -#define __SPI1_CLK_DISABLE __HAL_RCC_SPI1_CLK_DISABLE -#define __SPI1_CLK_ENABLE __HAL_RCC_SPI1_CLK_ENABLE -#define __SPI1_CLK_SLEEP_DISABLE __HAL_RCC_SPI1_CLK_SLEEP_DISABLE -#define __SPI1_CLK_SLEEP_ENABLE __HAL_RCC_SPI1_CLK_SLEEP_ENABLE -#define __SPI1_FORCE_RESET __HAL_RCC_SPI1_FORCE_RESET -#define __SPI1_RELEASE_RESET __HAL_RCC_SPI1_RELEASE_RESET -#define __SPI2_CLK_DISABLE __HAL_RCC_SPI2_CLK_DISABLE -#define __SPI2_CLK_ENABLE __HAL_RCC_SPI2_CLK_ENABLE -#define __SPI2_CLK_SLEEP_DISABLE __HAL_RCC_SPI2_CLK_SLEEP_DISABLE -#define __SPI2_CLK_SLEEP_ENABLE __HAL_RCC_SPI2_CLK_SLEEP_ENABLE -#define __SPI2_FORCE_RESET __HAL_RCC_SPI2_FORCE_RESET -#define __SPI2_RELEASE_RESET __HAL_RCC_SPI2_RELEASE_RESET -#define __SPI3_CLK_DISABLE __HAL_RCC_SPI3_CLK_DISABLE -#define __SPI3_CLK_ENABLE __HAL_RCC_SPI3_CLK_ENABLE -#define __SPI3_CLK_SLEEP_DISABLE __HAL_RCC_SPI3_CLK_SLEEP_DISABLE -#define __SPI3_CLK_SLEEP_ENABLE __HAL_RCC_SPI3_CLK_SLEEP_ENABLE -#define __SPI3_FORCE_RESET __HAL_RCC_SPI3_FORCE_RESET -#define __SPI3_RELEASE_RESET __HAL_RCC_SPI3_RELEASE_RESET -#define __SRAM_CLK_DISABLE __HAL_RCC_SRAM_CLK_DISABLE -#define __SRAM_CLK_ENABLE __HAL_RCC_SRAM_CLK_ENABLE -#define __SRAM1_CLK_SLEEP_DISABLE __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE -#define __SRAM1_CLK_SLEEP_ENABLE __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE -#define __SRAM2_CLK_SLEEP_DISABLE __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE -#define __SRAM2_CLK_SLEEP_ENABLE __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE -#define __SWPMI1_CLK_DISABLE __HAL_RCC_SWPMI1_CLK_DISABLE -#define __SWPMI1_CLK_ENABLE __HAL_RCC_SWPMI1_CLK_ENABLE -#define __SWPMI1_CLK_SLEEP_DISABLE __HAL_RCC_SWPMI1_CLK_SLEEP_DISABLE -#define __SWPMI1_CLK_SLEEP_ENABLE __HAL_RCC_SWPMI1_CLK_SLEEP_ENABLE -#define __SWPMI1_FORCE_RESET __HAL_RCC_SWPMI1_FORCE_RESET -#define __SWPMI1_RELEASE_RESET __HAL_RCC_SWPMI1_RELEASE_RESET -#define __SYSCFG_CLK_DISABLE __HAL_RCC_SYSCFG_CLK_DISABLE -#define __SYSCFG_CLK_ENABLE __HAL_RCC_SYSCFG_CLK_ENABLE -#define __SYSCFG_CLK_SLEEP_DISABLE __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE -#define __SYSCFG_CLK_SLEEP_ENABLE __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE -#define __SYSCFG_FORCE_RESET __HAL_RCC_SYSCFG_FORCE_RESET -#define __SYSCFG_RELEASE_RESET __HAL_RCC_SYSCFG_RELEASE_RESET -#define __TIM1_CLK_DISABLE __HAL_RCC_TIM1_CLK_DISABLE -#define __TIM1_CLK_ENABLE __HAL_RCC_TIM1_CLK_ENABLE -#define __TIM1_CLK_SLEEP_DISABLE __HAL_RCC_TIM1_CLK_SLEEP_DISABLE -#define __TIM1_CLK_SLEEP_ENABLE __HAL_RCC_TIM1_CLK_SLEEP_ENABLE -#define __TIM1_FORCE_RESET __HAL_RCC_TIM1_FORCE_RESET -#define __TIM1_RELEASE_RESET __HAL_RCC_TIM1_RELEASE_RESET -#define __TIM10_CLK_DISABLE __HAL_RCC_TIM10_CLK_DISABLE -#define __TIM10_CLK_ENABLE __HAL_RCC_TIM10_CLK_ENABLE -#define __TIM10_FORCE_RESET __HAL_RCC_TIM10_FORCE_RESET -#define __TIM10_RELEASE_RESET __HAL_RCC_TIM10_RELEASE_RESET -#define __TIM11_CLK_DISABLE __HAL_RCC_TIM11_CLK_DISABLE -#define __TIM11_CLK_ENABLE __HAL_RCC_TIM11_CLK_ENABLE -#define __TIM11_FORCE_RESET __HAL_RCC_TIM11_FORCE_RESET -#define __TIM11_RELEASE_RESET __HAL_RCC_TIM11_RELEASE_RESET -#define __TIM12_CLK_DISABLE __HAL_RCC_TIM12_CLK_DISABLE -#define __TIM12_CLK_ENABLE __HAL_RCC_TIM12_CLK_ENABLE -#define __TIM12_FORCE_RESET __HAL_RCC_TIM12_FORCE_RESET -#define __TIM12_RELEASE_RESET __HAL_RCC_TIM12_RELEASE_RESET -#define __TIM13_CLK_DISABLE __HAL_RCC_TIM13_CLK_DISABLE -#define __TIM13_CLK_ENABLE __HAL_RCC_TIM13_CLK_ENABLE -#define __TIM13_FORCE_RESET __HAL_RCC_TIM13_FORCE_RESET -#define __TIM13_RELEASE_RESET __HAL_RCC_TIM13_RELEASE_RESET -#define __TIM14_CLK_DISABLE __HAL_RCC_TIM14_CLK_DISABLE -#define __TIM14_CLK_ENABLE __HAL_RCC_TIM14_CLK_ENABLE -#define __TIM14_FORCE_RESET __HAL_RCC_TIM14_FORCE_RESET -#define __TIM14_RELEASE_RESET __HAL_RCC_TIM14_RELEASE_RESET -#define __TIM15_CLK_DISABLE __HAL_RCC_TIM15_CLK_DISABLE -#define __TIM15_CLK_ENABLE __HAL_RCC_TIM15_CLK_ENABLE -#define __TIM15_CLK_SLEEP_DISABLE __HAL_RCC_TIM15_CLK_SLEEP_DISABLE -#define __TIM15_CLK_SLEEP_ENABLE __HAL_RCC_TIM15_CLK_SLEEP_ENABLE -#define __TIM15_FORCE_RESET __HAL_RCC_TIM15_FORCE_RESET -#define __TIM15_RELEASE_RESET __HAL_RCC_TIM15_RELEASE_RESET -#define __TIM16_CLK_DISABLE __HAL_RCC_TIM16_CLK_DISABLE -#define __TIM16_CLK_ENABLE __HAL_RCC_TIM16_CLK_ENABLE -#define __TIM16_CLK_SLEEP_DISABLE __HAL_RCC_TIM16_CLK_SLEEP_DISABLE -#define __TIM16_CLK_SLEEP_ENABLE __HAL_RCC_TIM16_CLK_SLEEP_ENABLE -#define __TIM16_FORCE_RESET __HAL_RCC_TIM16_FORCE_RESET -#define __TIM16_RELEASE_RESET __HAL_RCC_TIM16_RELEASE_RESET -#define __TIM17_CLK_DISABLE __HAL_RCC_TIM17_CLK_DISABLE -#define __TIM17_CLK_ENABLE __HAL_RCC_TIM17_CLK_ENABLE -#define __TIM17_CLK_SLEEP_DISABLE __HAL_RCC_TIM17_CLK_SLEEP_DISABLE -#define __TIM17_CLK_SLEEP_ENABLE __HAL_RCC_TIM17_CLK_SLEEP_ENABLE -#define __TIM17_FORCE_RESET __HAL_RCC_TIM17_FORCE_RESET -#define __TIM17_RELEASE_RESET __HAL_RCC_TIM17_RELEASE_RESET -#define __TIM2_CLK_DISABLE __HAL_RCC_TIM2_CLK_DISABLE -#define __TIM2_CLK_ENABLE __HAL_RCC_TIM2_CLK_ENABLE -#define __TIM2_CLK_SLEEP_DISABLE __HAL_RCC_TIM2_CLK_SLEEP_DISABLE -#define __TIM2_CLK_SLEEP_ENABLE __HAL_RCC_TIM2_CLK_SLEEP_ENABLE -#define __TIM2_FORCE_RESET __HAL_RCC_TIM2_FORCE_RESET -#define __TIM2_RELEASE_RESET __HAL_RCC_TIM2_RELEASE_RESET -#define __TIM3_CLK_DISABLE __HAL_RCC_TIM3_CLK_DISABLE -#define __TIM3_CLK_ENABLE __HAL_RCC_TIM3_CLK_ENABLE -#define __TIM3_CLK_SLEEP_DISABLE __HAL_RCC_TIM3_CLK_SLEEP_DISABLE -#define __TIM3_CLK_SLEEP_ENABLE __HAL_RCC_TIM3_CLK_SLEEP_ENABLE -#define __TIM3_FORCE_RESET __HAL_RCC_TIM3_FORCE_RESET -#define __TIM3_RELEASE_RESET __HAL_RCC_TIM3_RELEASE_RESET -#define __TIM4_CLK_DISABLE __HAL_RCC_TIM4_CLK_DISABLE -#define __TIM4_CLK_ENABLE __HAL_RCC_TIM4_CLK_ENABLE -#define __TIM4_CLK_SLEEP_DISABLE __HAL_RCC_TIM4_CLK_SLEEP_DISABLE -#define __TIM4_CLK_SLEEP_ENABLE __HAL_RCC_TIM4_CLK_SLEEP_ENABLE -#define __TIM4_FORCE_RESET __HAL_RCC_TIM4_FORCE_RESET -#define __TIM4_RELEASE_RESET __HAL_RCC_TIM4_RELEASE_RESET -#define __TIM5_CLK_DISABLE __HAL_RCC_TIM5_CLK_DISABLE -#define __TIM5_CLK_ENABLE __HAL_RCC_TIM5_CLK_ENABLE -#define __TIM5_CLK_SLEEP_DISABLE __HAL_RCC_TIM5_CLK_SLEEP_DISABLE -#define __TIM5_CLK_SLEEP_ENABLE __HAL_RCC_TIM5_CLK_SLEEP_ENABLE -#define __TIM5_FORCE_RESET __HAL_RCC_TIM5_FORCE_RESET -#define __TIM5_RELEASE_RESET __HAL_RCC_TIM5_RELEASE_RESET -#define __TIM6_CLK_DISABLE __HAL_RCC_TIM6_CLK_DISABLE -#define __TIM6_CLK_ENABLE __HAL_RCC_TIM6_CLK_ENABLE -#define __TIM6_CLK_SLEEP_DISABLE __HAL_RCC_TIM6_CLK_SLEEP_DISABLE -#define __TIM6_CLK_SLEEP_ENABLE __HAL_RCC_TIM6_CLK_SLEEP_ENABLE -#define __TIM6_FORCE_RESET __HAL_RCC_TIM6_FORCE_RESET -#define __TIM6_RELEASE_RESET __HAL_RCC_TIM6_RELEASE_RESET -#define __TIM7_CLK_DISABLE __HAL_RCC_TIM7_CLK_DISABLE -#define __TIM7_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE -#define __TIM7_CLK_SLEEP_DISABLE __HAL_RCC_TIM7_CLK_SLEEP_DISABLE -#define __TIM7_CLK_SLEEP_ENABLE __HAL_RCC_TIM7_CLK_SLEEP_ENABLE -#define __TIM7_FORCE_RESET __HAL_RCC_TIM7_FORCE_RESET -#define __TIM7_RELEASE_RESET __HAL_RCC_TIM7_RELEASE_RESET -#define __TIM8_CLK_DISABLE __HAL_RCC_TIM8_CLK_DISABLE -#define __TIM8_CLK_ENABLE __HAL_RCC_TIM8_CLK_ENABLE -#define __TIM8_CLK_SLEEP_DISABLE __HAL_RCC_TIM8_CLK_SLEEP_DISABLE -#define __TIM8_CLK_SLEEP_ENABLE __HAL_RCC_TIM8_CLK_SLEEP_ENABLE -#define __TIM8_FORCE_RESET __HAL_RCC_TIM8_FORCE_RESET -#define __TIM8_RELEASE_RESET __HAL_RCC_TIM8_RELEASE_RESET -#define __TIM9_CLK_DISABLE __HAL_RCC_TIM9_CLK_DISABLE -#define __TIM9_CLK_ENABLE __HAL_RCC_TIM9_CLK_ENABLE -#define __TIM9_FORCE_RESET __HAL_RCC_TIM9_FORCE_RESET -#define __TIM9_RELEASE_RESET __HAL_RCC_TIM9_RELEASE_RESET -#define __TSC_CLK_DISABLE __HAL_RCC_TSC_CLK_DISABLE -#define __TSC_CLK_ENABLE __HAL_RCC_TSC_CLK_ENABLE -#define __TSC_CLK_SLEEP_DISABLE __HAL_RCC_TSC_CLK_SLEEP_DISABLE -#define __TSC_CLK_SLEEP_ENABLE __HAL_RCC_TSC_CLK_SLEEP_ENABLE -#define __TSC_FORCE_RESET __HAL_RCC_TSC_FORCE_RESET -#define __TSC_RELEASE_RESET __HAL_RCC_TSC_RELEASE_RESET -#define __UART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __UART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __UART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __UART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __UART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __UART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __UART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __UART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __UART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __UART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __UART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __UART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART1_CLK_DISABLE __HAL_RCC_USART1_CLK_DISABLE -#define __USART1_CLK_ENABLE __HAL_RCC_USART1_CLK_ENABLE -#define __USART1_CLK_SLEEP_DISABLE __HAL_RCC_USART1_CLK_SLEEP_DISABLE -#define __USART1_CLK_SLEEP_ENABLE __HAL_RCC_USART1_CLK_SLEEP_ENABLE -#define __USART1_FORCE_RESET __HAL_RCC_USART1_FORCE_RESET -#define __USART1_RELEASE_RESET __HAL_RCC_USART1_RELEASE_RESET -#define __USART2_CLK_DISABLE __HAL_RCC_USART2_CLK_DISABLE -#define __USART2_CLK_ENABLE __HAL_RCC_USART2_CLK_ENABLE -#define __USART2_CLK_SLEEP_DISABLE __HAL_RCC_USART2_CLK_SLEEP_DISABLE -#define __USART2_CLK_SLEEP_ENABLE __HAL_RCC_USART2_CLK_SLEEP_ENABLE -#define __USART2_FORCE_RESET __HAL_RCC_USART2_FORCE_RESET -#define __USART2_RELEASE_RESET __HAL_RCC_USART2_RELEASE_RESET -#define __USART3_CLK_DISABLE __HAL_RCC_USART3_CLK_DISABLE -#define __USART3_CLK_ENABLE __HAL_RCC_USART3_CLK_ENABLE -#define __USART3_CLK_SLEEP_DISABLE __HAL_RCC_USART3_CLK_SLEEP_DISABLE -#define __USART3_CLK_SLEEP_ENABLE __HAL_RCC_USART3_CLK_SLEEP_ENABLE -#define __USART3_FORCE_RESET __HAL_RCC_USART3_FORCE_RESET -#define __USART3_RELEASE_RESET __HAL_RCC_USART3_RELEASE_RESET -#define __USART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __USART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __USART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __USART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __USART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __USART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __USART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __USART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __USART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __USART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __USART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __USART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __USART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __USART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __USART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __USART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __USART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __USART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __USART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __USB_CLK_DISABLE __HAL_RCC_USB_CLK_DISABLE -#define __USB_CLK_ENABLE __HAL_RCC_USB_CLK_ENABLE -#define __USB_FORCE_RESET __HAL_RCC_USB_FORCE_RESET -#define __USB_CLK_SLEEP_ENABLE __HAL_RCC_USB_CLK_SLEEP_ENABLE -#define __USB_CLK_SLEEP_DISABLE __HAL_RCC_USB_CLK_SLEEP_DISABLE -#define __USB_OTG_FS_CLK_DISABLE __HAL_RCC_USB_OTG_FS_CLK_DISABLE -#define __USB_OTG_FS_CLK_ENABLE __HAL_RCC_USB_OTG_FS_CLK_ENABLE -#define __USB_RELEASE_RESET __HAL_RCC_USB_RELEASE_RESET - -#if defined(STM32H7) -#define __HAL_RCC_WWDG_CLK_DISABLE __HAL_RCC_WWDG1_CLK_DISABLE -#define __HAL_RCC_WWDG_CLK_ENABLE __HAL_RCC_WWDG1_CLK_ENABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG1_CLK_SLEEP_DISABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG1_CLK_SLEEP_ENABLE - -#define __HAL_RCC_WWDG_FORCE_RESET ((void)0U) /* Not available on the STM32H7*/ -#define __HAL_RCC_WWDG_RELEASE_RESET ((void)0U) /* Not available on the STM32H7*/ - - -#define __HAL_RCC_WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG1_IS_CLK_ENABLED -#define __HAL_RCC_WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG1_IS_CLK_DISABLED -#endif - -#define __WWDG_CLK_DISABLE __HAL_RCC_WWDG_CLK_DISABLE -#define __WWDG_CLK_ENABLE __HAL_RCC_WWDG_CLK_ENABLE -#define __WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG_CLK_SLEEP_DISABLE -#define __WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG_CLK_SLEEP_ENABLE -#define __WWDG_FORCE_RESET __HAL_RCC_WWDG_FORCE_RESET -#define __WWDG_RELEASE_RESET __HAL_RCC_WWDG_RELEASE_RESET - -#define __TIM21_CLK_ENABLE __HAL_RCC_TIM21_CLK_ENABLE -#define __TIM21_CLK_DISABLE __HAL_RCC_TIM21_CLK_DISABLE -#define __TIM21_FORCE_RESET __HAL_RCC_TIM21_FORCE_RESET -#define __TIM21_RELEASE_RESET __HAL_RCC_TIM21_RELEASE_RESET -#define __TIM21_CLK_SLEEP_ENABLE __HAL_RCC_TIM21_CLK_SLEEP_ENABLE -#define __TIM21_CLK_SLEEP_DISABLE __HAL_RCC_TIM21_CLK_SLEEP_DISABLE -#define __TIM22_CLK_ENABLE __HAL_RCC_TIM22_CLK_ENABLE -#define __TIM22_CLK_DISABLE __HAL_RCC_TIM22_CLK_DISABLE -#define __TIM22_FORCE_RESET __HAL_RCC_TIM22_FORCE_RESET -#define __TIM22_RELEASE_RESET __HAL_RCC_TIM22_RELEASE_RESET -#define __TIM22_CLK_SLEEP_ENABLE __HAL_RCC_TIM22_CLK_SLEEP_ENABLE -#define __TIM22_CLK_SLEEP_DISABLE __HAL_RCC_TIM22_CLK_SLEEP_DISABLE -#define __CRS_CLK_DISABLE __HAL_RCC_CRS_CLK_DISABLE -#define __CRS_CLK_ENABLE __HAL_RCC_CRS_CLK_ENABLE -#define __CRS_CLK_SLEEP_DISABLE __HAL_RCC_CRS_CLK_SLEEP_DISABLE -#define __CRS_CLK_SLEEP_ENABLE __HAL_RCC_CRS_CLK_SLEEP_ENABLE -#define __CRS_FORCE_RESET __HAL_RCC_CRS_FORCE_RESET -#define __CRS_RELEASE_RESET __HAL_RCC_CRS_RELEASE_RESET -#define __RCC_BACKUPRESET_FORCE __HAL_RCC_BACKUPRESET_FORCE -#define __RCC_BACKUPRESET_RELEASE __HAL_RCC_BACKUPRESET_RELEASE - -#define __USB_OTG_FS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __USB_OTG_FS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET -#define __USB_OTG_FS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE -#define __USB_OTG_FS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE -#define __USB_OTG_HS_CLK_DISABLE __HAL_RCC_USB_OTG_HS_CLK_DISABLE -#define __USB_OTG_HS_CLK_ENABLE __HAL_RCC_USB_OTG_HS_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE -#define __TIM9_CLK_SLEEP_ENABLE __HAL_RCC_TIM9_CLK_SLEEP_ENABLE -#define __TIM9_CLK_SLEEP_DISABLE __HAL_RCC_TIM9_CLK_SLEEP_DISABLE -#define __TIM10_CLK_SLEEP_ENABLE __HAL_RCC_TIM10_CLK_SLEEP_ENABLE -#define __TIM10_CLK_SLEEP_DISABLE __HAL_RCC_TIM10_CLK_SLEEP_DISABLE -#define __TIM11_CLK_SLEEP_ENABLE __HAL_RCC_TIM11_CLK_SLEEP_ENABLE -#define __TIM11_CLK_SLEEP_DISABLE __HAL_RCC_TIM11_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE -#define __ETHMACPTP_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_ENABLE __HAL_RCC_ETHMACPTP_CLK_ENABLE -#define __ETHMACPTP_CLK_DISABLE __HAL_RCC_ETHMACPTP_CLK_DISABLE -#define __HASH_CLK_ENABLE __HAL_RCC_HASH_CLK_ENABLE -#define __HASH_FORCE_RESET __HAL_RCC_HASH_FORCE_RESET -#define __HASH_RELEASE_RESET __HAL_RCC_HASH_RELEASE_RESET -#define __HASH_CLK_SLEEP_ENABLE __HAL_RCC_HASH_CLK_SLEEP_ENABLE -#define __HASH_CLK_SLEEP_DISABLE __HAL_RCC_HASH_CLK_SLEEP_DISABLE -#define __HASH_CLK_DISABLE __HAL_RCC_HASH_CLK_DISABLE -#define __SPI5_CLK_ENABLE __HAL_RCC_SPI5_CLK_ENABLE -#define __SPI5_CLK_DISABLE __HAL_RCC_SPI5_CLK_DISABLE -#define __SPI5_FORCE_RESET __HAL_RCC_SPI5_FORCE_RESET -#define __SPI5_RELEASE_RESET __HAL_RCC_SPI5_RELEASE_RESET -#define __SPI5_CLK_SLEEP_ENABLE __HAL_RCC_SPI5_CLK_SLEEP_ENABLE -#define __SPI5_CLK_SLEEP_DISABLE __HAL_RCC_SPI5_CLK_SLEEP_DISABLE -#define __SPI6_CLK_ENABLE __HAL_RCC_SPI6_CLK_ENABLE -#define __SPI6_CLK_DISABLE __HAL_RCC_SPI6_CLK_DISABLE -#define __SPI6_FORCE_RESET __HAL_RCC_SPI6_FORCE_RESET -#define __SPI6_RELEASE_RESET __HAL_RCC_SPI6_RELEASE_RESET -#define __SPI6_CLK_SLEEP_ENABLE __HAL_RCC_SPI6_CLK_SLEEP_ENABLE -#define __SPI6_CLK_SLEEP_DISABLE __HAL_RCC_SPI6_CLK_SLEEP_DISABLE -#define __LTDC_CLK_ENABLE __HAL_RCC_LTDC_CLK_ENABLE -#define __LTDC_CLK_DISABLE __HAL_RCC_LTDC_CLK_DISABLE -#define __LTDC_FORCE_RESET __HAL_RCC_LTDC_FORCE_RESET -#define __LTDC_RELEASE_RESET __HAL_RCC_LTDC_RELEASE_RESET -#define __LTDC_CLK_SLEEP_ENABLE __HAL_RCC_LTDC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_ENABLE __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_DISABLE __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE -#define __ETHMACTX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE -#define __ETHMACTX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE -#define __ETHMACRX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE -#define __ETHMACRX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE -#define __TIM12_CLK_SLEEP_ENABLE __HAL_RCC_TIM12_CLK_SLEEP_ENABLE -#define __TIM12_CLK_SLEEP_DISABLE __HAL_RCC_TIM12_CLK_SLEEP_DISABLE -#define __TIM13_CLK_SLEEP_ENABLE __HAL_RCC_TIM13_CLK_SLEEP_ENABLE -#define __TIM13_CLK_SLEEP_DISABLE __HAL_RCC_TIM13_CLK_SLEEP_DISABLE -#define __TIM14_CLK_SLEEP_ENABLE __HAL_RCC_TIM14_CLK_SLEEP_ENABLE -#define __TIM14_CLK_SLEEP_DISABLE __HAL_RCC_TIM14_CLK_SLEEP_DISABLE -#define __BKPSRAM_CLK_ENABLE __HAL_RCC_BKPSRAM_CLK_ENABLE -#define __BKPSRAM_CLK_DISABLE __HAL_RCC_BKPSRAM_CLK_DISABLE -#define __BKPSRAM_CLK_SLEEP_ENABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE -#define __BKPSRAM_CLK_SLEEP_DISABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE -#define __CCMDATARAMEN_CLK_ENABLE __HAL_RCC_CCMDATARAMEN_CLK_ENABLE -#define __CCMDATARAMEN_CLK_DISABLE __HAL_RCC_CCMDATARAMEN_CLK_DISABLE -#define __USART6_CLK_ENABLE __HAL_RCC_USART6_CLK_ENABLE -#define __USART6_CLK_DISABLE __HAL_RCC_USART6_CLK_DISABLE -#define __USART6_FORCE_RESET __HAL_RCC_USART6_FORCE_RESET -#define __USART6_RELEASE_RESET __HAL_RCC_USART6_RELEASE_RESET -#define __USART6_CLK_SLEEP_ENABLE __HAL_RCC_USART6_CLK_SLEEP_ENABLE -#define __USART6_CLK_SLEEP_DISABLE __HAL_RCC_USART6_CLK_SLEEP_DISABLE -#define __SPI4_CLK_ENABLE __HAL_RCC_SPI4_CLK_ENABLE -#define __SPI4_CLK_DISABLE __HAL_RCC_SPI4_CLK_DISABLE -#define __SPI4_FORCE_RESET __HAL_RCC_SPI4_FORCE_RESET -#define __SPI4_RELEASE_RESET __HAL_RCC_SPI4_RELEASE_RESET -#define __SPI4_CLK_SLEEP_ENABLE __HAL_RCC_SPI4_CLK_SLEEP_ENABLE -#define __SPI4_CLK_SLEEP_DISABLE __HAL_RCC_SPI4_CLK_SLEEP_DISABLE -#define __GPIOI_CLK_ENABLE __HAL_RCC_GPIOI_CLK_ENABLE -#define __GPIOI_CLK_DISABLE __HAL_RCC_GPIOI_CLK_DISABLE -#define __GPIOI_FORCE_RESET __HAL_RCC_GPIOI_FORCE_RESET -#define __GPIOI_RELEASE_RESET __HAL_RCC_GPIOI_RELEASE_RESET -#define __GPIOI_CLK_SLEEP_ENABLE __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE -#define __GPIOI_CLK_SLEEP_DISABLE __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE -#define __GPIOJ_CLK_ENABLE __HAL_RCC_GPIOJ_CLK_ENABLE -#define __GPIOJ_CLK_DISABLE __HAL_RCC_GPIOJ_CLK_DISABLE -#define __GPIOJ_FORCE_RESET __HAL_RCC_GPIOJ_FORCE_RESET -#define __GPIOJ_RELEASE_RESET __HAL_RCC_GPIOJ_RELEASE_RESET -#define __GPIOJ_CLK_SLEEP_ENABLE __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE -#define __GPIOJ_CLK_SLEEP_DISABLE __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE -#define __GPIOK_CLK_ENABLE __HAL_RCC_GPIOK_CLK_ENABLE -#define __GPIOK_CLK_DISABLE __HAL_RCC_GPIOK_CLK_DISABLE -#define __GPIOK_RELEASE_RESET __HAL_RCC_GPIOK_RELEASE_RESET -#define __GPIOK_CLK_SLEEP_ENABLE __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE -#define __GPIOK_CLK_SLEEP_DISABLE __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE -#define __ETH_CLK_ENABLE __HAL_RCC_ETH_CLK_ENABLE -#define __ETH_CLK_DISABLE __HAL_RCC_ETH_CLK_DISABLE -#define __DCMI_CLK_ENABLE __HAL_RCC_DCMI_CLK_ENABLE -#define __DCMI_CLK_DISABLE __HAL_RCC_DCMI_CLK_DISABLE -#define __DCMI_FORCE_RESET __HAL_RCC_DCMI_FORCE_RESET -#define __DCMI_RELEASE_RESET __HAL_RCC_DCMI_RELEASE_RESET -#define __DCMI_CLK_SLEEP_ENABLE __HAL_RCC_DCMI_CLK_SLEEP_ENABLE -#define __DCMI_CLK_SLEEP_DISABLE __HAL_RCC_DCMI_CLK_SLEEP_DISABLE -#define __UART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __UART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __UART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __UART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __UART7_CLK_SLEEP_ENABLE __HAL_RCC_UART7_CLK_SLEEP_ENABLE -#define __UART7_CLK_SLEEP_DISABLE __HAL_RCC_UART7_CLK_SLEEP_DISABLE -#define __UART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __UART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __UART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __UART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __UART8_CLK_SLEEP_ENABLE __HAL_RCC_UART8_CLK_SLEEP_ENABLE -#define __UART8_CLK_SLEEP_DISABLE __HAL_RCC_UART8_CLK_SLEEP_DISABLE -#define __OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_DISABLED -#define __HAL_RCC_OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __HAL_RCC_OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_DISABLED -#define __SRAM3_CLK_SLEEP_ENABLE __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_ENABLE __HAL_RCC_CAN2_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_DISABLE __HAL_RCC_CAN2_CLK_SLEEP_DISABLE -#define __DAC_CLK_SLEEP_ENABLE __HAL_RCC_DAC_CLK_SLEEP_ENABLE -#define __DAC_CLK_SLEEP_DISABLE __HAL_RCC_DAC_CLK_SLEEP_DISABLE -#define __ADC2_CLK_SLEEP_ENABLE __HAL_RCC_ADC2_CLK_SLEEP_ENABLE -#define __ADC2_CLK_SLEEP_DISABLE __HAL_RCC_ADC2_CLK_SLEEP_DISABLE -#define __ADC3_CLK_SLEEP_ENABLE __HAL_RCC_ADC3_CLK_SLEEP_ENABLE -#define __ADC3_CLK_SLEEP_DISABLE __HAL_RCC_ADC3_CLK_SLEEP_DISABLE -#define __FSMC_FORCE_RESET __HAL_RCC_FSMC_FORCE_RESET -#define __FSMC_RELEASE_RESET __HAL_RCC_FSMC_RELEASE_RESET -#define __FSMC_CLK_SLEEP_ENABLE __HAL_RCC_FSMC_CLK_SLEEP_ENABLE -#define __FSMC_CLK_SLEEP_DISABLE __HAL_RCC_FSMC_CLK_SLEEP_DISABLE -#define __SDIO_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __SDIO_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_ENABLE __HAL_RCC_DMA2D_CLK_ENABLE -#define __DMA2D_CLK_DISABLE __HAL_RCC_DMA2D_CLK_DISABLE -#define __DMA2D_FORCE_RESET __HAL_RCC_DMA2D_FORCE_RESET -#define __DMA2D_RELEASE_RESET __HAL_RCC_DMA2D_RELEASE_RESET -#define __DMA2D_CLK_SLEEP_ENABLE __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_SLEEP_DISABLE __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE - -/* alias define maintained for legacy */ -#define __HAL_RCC_OTGFS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __HAL_RCC_OTGFS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET - -#define __ADC12_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE -#define __ADC12_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE -#define __ADC34_CLK_ENABLE __HAL_RCC_ADC34_CLK_ENABLE -#define __ADC34_CLK_DISABLE __HAL_RCC_ADC34_CLK_DISABLE -#define __DAC2_CLK_ENABLE __HAL_RCC_DAC2_CLK_ENABLE -#define __DAC2_CLK_DISABLE __HAL_RCC_DAC2_CLK_DISABLE -#define __TIM18_CLK_ENABLE __HAL_RCC_TIM18_CLK_ENABLE -#define __TIM18_CLK_DISABLE __HAL_RCC_TIM18_CLK_DISABLE -#define __TIM19_CLK_ENABLE __HAL_RCC_TIM19_CLK_ENABLE -#define __TIM19_CLK_DISABLE __HAL_RCC_TIM19_CLK_DISABLE -#define __TIM20_CLK_ENABLE __HAL_RCC_TIM20_CLK_ENABLE -#define __TIM20_CLK_DISABLE __HAL_RCC_TIM20_CLK_DISABLE -#define __HRTIM1_CLK_ENABLE __HAL_RCC_HRTIM1_CLK_ENABLE -#define __HRTIM1_CLK_DISABLE __HAL_RCC_HRTIM1_CLK_DISABLE -#define __SDADC1_CLK_ENABLE __HAL_RCC_SDADC1_CLK_ENABLE -#define __SDADC2_CLK_ENABLE __HAL_RCC_SDADC2_CLK_ENABLE -#define __SDADC3_CLK_ENABLE __HAL_RCC_SDADC3_CLK_ENABLE -#define __SDADC1_CLK_DISABLE __HAL_RCC_SDADC1_CLK_DISABLE -#define __SDADC2_CLK_DISABLE __HAL_RCC_SDADC2_CLK_DISABLE -#define __SDADC3_CLK_DISABLE __HAL_RCC_SDADC3_CLK_DISABLE - -#define __ADC12_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET -#define __ADC12_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET -#define __ADC34_FORCE_RESET __HAL_RCC_ADC34_FORCE_RESET -#define __ADC34_RELEASE_RESET __HAL_RCC_ADC34_RELEASE_RESET -#define __DAC2_FORCE_RESET __HAL_RCC_DAC2_FORCE_RESET -#define __DAC2_RELEASE_RESET __HAL_RCC_DAC2_RELEASE_RESET -#define __TIM18_FORCE_RESET __HAL_RCC_TIM18_FORCE_RESET -#define __TIM18_RELEASE_RESET __HAL_RCC_TIM18_RELEASE_RESET -#define __TIM19_FORCE_RESET __HAL_RCC_TIM19_FORCE_RESET -#define __TIM19_RELEASE_RESET __HAL_RCC_TIM19_RELEASE_RESET -#define __TIM20_FORCE_RESET __HAL_RCC_TIM20_FORCE_RESET -#define __TIM20_RELEASE_RESET __HAL_RCC_TIM20_RELEASE_RESET -#define __HRTIM1_FORCE_RESET __HAL_RCC_HRTIM1_FORCE_RESET -#define __HRTIM1_RELEASE_RESET __HAL_RCC_HRTIM1_RELEASE_RESET -#define __SDADC1_FORCE_RESET __HAL_RCC_SDADC1_FORCE_RESET -#define __SDADC2_FORCE_RESET __HAL_RCC_SDADC2_FORCE_RESET -#define __SDADC3_FORCE_RESET __HAL_RCC_SDADC3_FORCE_RESET -#define __SDADC1_RELEASE_RESET __HAL_RCC_SDADC1_RELEASE_RESET -#define __SDADC2_RELEASE_RESET __HAL_RCC_SDADC2_RELEASE_RESET -#define __SDADC3_RELEASE_RESET __HAL_RCC_SDADC3_RELEASE_RESET - -#define __ADC1_IS_CLK_ENABLED __HAL_RCC_ADC1_IS_CLK_ENABLED -#define __ADC1_IS_CLK_DISABLED __HAL_RCC_ADC1_IS_CLK_DISABLED -#define __ADC12_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED -#define __ADC12_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED -#define __ADC34_IS_CLK_ENABLED __HAL_RCC_ADC34_IS_CLK_ENABLED -#define __ADC34_IS_CLK_DISABLED __HAL_RCC_ADC34_IS_CLK_DISABLED -#define __CEC_IS_CLK_ENABLED __HAL_RCC_CEC_IS_CLK_ENABLED -#define __CEC_IS_CLK_DISABLED __HAL_RCC_CEC_IS_CLK_DISABLED -#define __CRC_IS_CLK_ENABLED __HAL_RCC_CRC_IS_CLK_ENABLED -#define __CRC_IS_CLK_DISABLED __HAL_RCC_CRC_IS_CLK_DISABLED -#define __DAC1_IS_CLK_ENABLED __HAL_RCC_DAC1_IS_CLK_ENABLED -#define __DAC1_IS_CLK_DISABLED __HAL_RCC_DAC1_IS_CLK_DISABLED -#define __DAC2_IS_CLK_ENABLED __HAL_RCC_DAC2_IS_CLK_ENABLED -#define __DAC2_IS_CLK_DISABLED __HAL_RCC_DAC2_IS_CLK_DISABLED -#define __DMA1_IS_CLK_ENABLED __HAL_RCC_DMA1_IS_CLK_ENABLED -#define __DMA1_IS_CLK_DISABLED __HAL_RCC_DMA1_IS_CLK_DISABLED -#define __DMA2_IS_CLK_ENABLED __HAL_RCC_DMA2_IS_CLK_ENABLED -#define __DMA2_IS_CLK_DISABLED __HAL_RCC_DMA2_IS_CLK_DISABLED -#define __FLITF_IS_CLK_ENABLED __HAL_RCC_FLITF_IS_CLK_ENABLED -#define __FLITF_IS_CLK_DISABLED __HAL_RCC_FLITF_IS_CLK_DISABLED -#define __FMC_IS_CLK_ENABLED __HAL_RCC_FMC_IS_CLK_ENABLED -#define __FMC_IS_CLK_DISABLED __HAL_RCC_FMC_IS_CLK_DISABLED -#define __GPIOA_IS_CLK_ENABLED __HAL_RCC_GPIOA_IS_CLK_ENABLED -#define __GPIOA_IS_CLK_DISABLED __HAL_RCC_GPIOA_IS_CLK_DISABLED -#define __GPIOB_IS_CLK_ENABLED __HAL_RCC_GPIOB_IS_CLK_ENABLED -#define __GPIOB_IS_CLK_DISABLED __HAL_RCC_GPIOB_IS_CLK_DISABLED -#define __GPIOC_IS_CLK_ENABLED __HAL_RCC_GPIOC_IS_CLK_ENABLED -#define __GPIOC_IS_CLK_DISABLED __HAL_RCC_GPIOC_IS_CLK_DISABLED -#define __GPIOD_IS_CLK_ENABLED __HAL_RCC_GPIOD_IS_CLK_ENABLED -#define __GPIOD_IS_CLK_DISABLED __HAL_RCC_GPIOD_IS_CLK_DISABLED -#define __GPIOE_IS_CLK_ENABLED __HAL_RCC_GPIOE_IS_CLK_ENABLED -#define __GPIOE_IS_CLK_DISABLED __HAL_RCC_GPIOE_IS_CLK_DISABLED -#define __GPIOF_IS_CLK_ENABLED __HAL_RCC_GPIOF_IS_CLK_ENABLED -#define __GPIOF_IS_CLK_DISABLED __HAL_RCC_GPIOF_IS_CLK_DISABLED -#define __GPIOG_IS_CLK_ENABLED __HAL_RCC_GPIOG_IS_CLK_ENABLED -#define __GPIOG_IS_CLK_DISABLED __HAL_RCC_GPIOG_IS_CLK_DISABLED -#define __GPIOH_IS_CLK_ENABLED __HAL_RCC_GPIOH_IS_CLK_ENABLED -#define __GPIOH_IS_CLK_DISABLED __HAL_RCC_GPIOH_IS_CLK_DISABLED -#define __HRTIM1_IS_CLK_ENABLED __HAL_RCC_HRTIM1_IS_CLK_ENABLED -#define __HRTIM1_IS_CLK_DISABLED __HAL_RCC_HRTIM1_IS_CLK_DISABLED -#define __I2C1_IS_CLK_ENABLED __HAL_RCC_I2C1_IS_CLK_ENABLED -#define __I2C1_IS_CLK_DISABLED __HAL_RCC_I2C1_IS_CLK_DISABLED -#define __I2C2_IS_CLK_ENABLED __HAL_RCC_I2C2_IS_CLK_ENABLED -#define __I2C2_IS_CLK_DISABLED __HAL_RCC_I2C2_IS_CLK_DISABLED -#define __I2C3_IS_CLK_ENABLED __HAL_RCC_I2C3_IS_CLK_ENABLED -#define __I2C3_IS_CLK_DISABLED __HAL_RCC_I2C3_IS_CLK_DISABLED -#define __PWR_IS_CLK_ENABLED __HAL_RCC_PWR_IS_CLK_ENABLED -#define __PWR_IS_CLK_DISABLED __HAL_RCC_PWR_IS_CLK_DISABLED -#define __SYSCFG_IS_CLK_ENABLED __HAL_RCC_SYSCFG_IS_CLK_ENABLED -#define __SYSCFG_IS_CLK_DISABLED __HAL_RCC_SYSCFG_IS_CLK_DISABLED -#define __SPI1_IS_CLK_ENABLED __HAL_RCC_SPI1_IS_CLK_ENABLED -#define __SPI1_IS_CLK_DISABLED __HAL_RCC_SPI1_IS_CLK_DISABLED -#define __SPI2_IS_CLK_ENABLED __HAL_RCC_SPI2_IS_CLK_ENABLED -#define __SPI2_IS_CLK_DISABLED __HAL_RCC_SPI2_IS_CLK_DISABLED -#define __SPI3_IS_CLK_ENABLED __HAL_RCC_SPI3_IS_CLK_ENABLED -#define __SPI3_IS_CLK_DISABLED __HAL_RCC_SPI3_IS_CLK_DISABLED -#define __SPI4_IS_CLK_ENABLED __HAL_RCC_SPI4_IS_CLK_ENABLED -#define __SPI4_IS_CLK_DISABLED __HAL_RCC_SPI4_IS_CLK_DISABLED -#define __SDADC1_IS_CLK_ENABLED __HAL_RCC_SDADC1_IS_CLK_ENABLED -#define __SDADC1_IS_CLK_DISABLED __HAL_RCC_SDADC1_IS_CLK_DISABLED -#define __SDADC2_IS_CLK_ENABLED __HAL_RCC_SDADC2_IS_CLK_ENABLED -#define __SDADC2_IS_CLK_DISABLED __HAL_RCC_SDADC2_IS_CLK_DISABLED -#define __SDADC3_IS_CLK_ENABLED __HAL_RCC_SDADC3_IS_CLK_ENABLED -#define __SDADC3_IS_CLK_DISABLED __HAL_RCC_SDADC3_IS_CLK_DISABLED -#define __SRAM_IS_CLK_ENABLED __HAL_RCC_SRAM_IS_CLK_ENABLED -#define __SRAM_IS_CLK_DISABLED __HAL_RCC_SRAM_IS_CLK_DISABLED -#define __TIM1_IS_CLK_ENABLED __HAL_RCC_TIM1_IS_CLK_ENABLED -#define __TIM1_IS_CLK_DISABLED __HAL_RCC_TIM1_IS_CLK_DISABLED -#define __TIM2_IS_CLK_ENABLED __HAL_RCC_TIM2_IS_CLK_ENABLED -#define __TIM2_IS_CLK_DISABLED __HAL_RCC_TIM2_IS_CLK_DISABLED -#define __TIM3_IS_CLK_ENABLED __HAL_RCC_TIM3_IS_CLK_ENABLED -#define __TIM3_IS_CLK_DISABLED __HAL_RCC_TIM3_IS_CLK_DISABLED -#define __TIM4_IS_CLK_ENABLED __HAL_RCC_TIM4_IS_CLK_ENABLED -#define __TIM4_IS_CLK_DISABLED __HAL_RCC_TIM4_IS_CLK_DISABLED -#define __TIM5_IS_CLK_ENABLED __HAL_RCC_TIM5_IS_CLK_ENABLED -#define __TIM5_IS_CLK_DISABLED __HAL_RCC_TIM5_IS_CLK_DISABLED -#define __TIM6_IS_CLK_ENABLED __HAL_RCC_TIM6_IS_CLK_ENABLED -#define __TIM6_IS_CLK_DISABLED __HAL_RCC_TIM6_IS_CLK_DISABLED -#define __TIM7_IS_CLK_ENABLED __HAL_RCC_TIM7_IS_CLK_ENABLED -#define __TIM7_IS_CLK_DISABLED __HAL_RCC_TIM7_IS_CLK_DISABLED -#define __TIM8_IS_CLK_ENABLED __HAL_RCC_TIM8_IS_CLK_ENABLED -#define __TIM8_IS_CLK_DISABLED __HAL_RCC_TIM8_IS_CLK_DISABLED -#define __TIM12_IS_CLK_ENABLED __HAL_RCC_TIM12_IS_CLK_ENABLED -#define __TIM12_IS_CLK_DISABLED __HAL_RCC_TIM12_IS_CLK_DISABLED -#define __TIM13_IS_CLK_ENABLED __HAL_RCC_TIM13_IS_CLK_ENABLED -#define __TIM13_IS_CLK_DISABLED __HAL_RCC_TIM13_IS_CLK_DISABLED -#define __TIM14_IS_CLK_ENABLED __HAL_RCC_TIM14_IS_CLK_ENABLED -#define __TIM14_IS_CLK_DISABLED __HAL_RCC_TIM14_IS_CLK_DISABLED -#define __TIM15_IS_CLK_ENABLED __HAL_RCC_TIM15_IS_CLK_ENABLED -#define __TIM15_IS_CLK_DISABLED __HAL_RCC_TIM15_IS_CLK_DISABLED -#define __TIM16_IS_CLK_ENABLED __HAL_RCC_TIM16_IS_CLK_ENABLED -#define __TIM16_IS_CLK_DISABLED __HAL_RCC_TIM16_IS_CLK_DISABLED -#define __TIM17_IS_CLK_ENABLED __HAL_RCC_TIM17_IS_CLK_ENABLED -#define __TIM17_IS_CLK_DISABLED __HAL_RCC_TIM17_IS_CLK_DISABLED -#define __TIM18_IS_CLK_ENABLED __HAL_RCC_TIM18_IS_CLK_ENABLED -#define __TIM18_IS_CLK_DISABLED __HAL_RCC_TIM18_IS_CLK_DISABLED -#define __TIM19_IS_CLK_ENABLED __HAL_RCC_TIM19_IS_CLK_ENABLED -#define __TIM19_IS_CLK_DISABLED __HAL_RCC_TIM19_IS_CLK_DISABLED -#define __TIM20_IS_CLK_ENABLED __HAL_RCC_TIM20_IS_CLK_ENABLED -#define __TIM20_IS_CLK_DISABLED __HAL_RCC_TIM20_IS_CLK_DISABLED -#define __TSC_IS_CLK_ENABLED __HAL_RCC_TSC_IS_CLK_ENABLED -#define __TSC_IS_CLK_DISABLED __HAL_RCC_TSC_IS_CLK_DISABLED -#define __UART4_IS_CLK_ENABLED __HAL_RCC_UART4_IS_CLK_ENABLED -#define __UART4_IS_CLK_DISABLED __HAL_RCC_UART4_IS_CLK_DISABLED -#define __UART5_IS_CLK_ENABLED __HAL_RCC_UART5_IS_CLK_ENABLED -#define __UART5_IS_CLK_DISABLED __HAL_RCC_UART5_IS_CLK_DISABLED -#define __USART1_IS_CLK_ENABLED __HAL_RCC_USART1_IS_CLK_ENABLED -#define __USART1_IS_CLK_DISABLED __HAL_RCC_USART1_IS_CLK_DISABLED -#define __USART2_IS_CLK_ENABLED __HAL_RCC_USART2_IS_CLK_ENABLED -#define __USART2_IS_CLK_DISABLED __HAL_RCC_USART2_IS_CLK_DISABLED -#define __USART3_IS_CLK_ENABLED __HAL_RCC_USART3_IS_CLK_ENABLED -#define __USART3_IS_CLK_DISABLED __HAL_RCC_USART3_IS_CLK_DISABLED -#define __USB_IS_CLK_ENABLED __HAL_RCC_USB_IS_CLK_ENABLED -#define __USB_IS_CLK_DISABLED __HAL_RCC_USB_IS_CLK_DISABLED -#define __WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG_IS_CLK_ENABLED -#define __WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG_IS_CLK_DISABLED - -#if defined(STM32L1) -#define __HAL_RCC_CRYP_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __HAL_RCC_CRYP_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __HAL_RCC_CRYP_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __HAL_RCC_CRYP_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#endif /* STM32L1 */ - -#if defined(STM32F4) -#define __HAL_RCC_SDMMC1_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __HAL_RCC_SDMMC1_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDMMC1_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __HAL_RCC_SDMMC1_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __HAL_RCC_SDMMC1_IS_CLK_ENABLED __HAL_RCC_SDIO_IS_CLK_ENABLED -#define __HAL_RCC_SDMMC1_IS_CLK_DISABLED __HAL_RCC_SDIO_IS_CLK_DISABLED -#define Sdmmc1ClockSelection SdioClockSelection -#define RCC_PERIPHCLK_SDMMC1 RCC_PERIPHCLK_SDIO -#define RCC_SDMMC1CLKSOURCE_CLK48 RCC_SDIOCLKSOURCE_CK48 -#define RCC_SDMMC1CLKSOURCE_SYSCLK RCC_SDIOCLKSOURCE_SYSCLK -#define __HAL_RCC_SDMMC1_CONFIG __HAL_RCC_SDIO_CONFIG -#define __HAL_RCC_GET_SDMMC1_SOURCE __HAL_RCC_GET_SDIO_SOURCE -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET -#define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE -#define __HAL_RCC_SDIO_CLK_DISABLE __HAL_RCC_SDMMC1_CLK_DISABLE -#define __HAL_RCC_SDIO_IS_CLK_ENABLED __HAL_RCC_SDMMC1_IS_CLK_ENABLED -#define __HAL_RCC_SDIO_IS_CLK_DISABLED __HAL_RCC_SDMMC1_IS_CLK_DISABLED -#define SdioClockSelection Sdmmc1ClockSelection -#define RCC_PERIPHCLK_SDIO RCC_PERIPHCLK_SDMMC1 -#define __HAL_RCC_SDIO_CONFIG __HAL_RCC_SDMMC1_CONFIG -#define __HAL_RCC_GET_SDIO_SOURCE __HAL_RCC_GET_SDMMC1_SOURCE -#endif - -#if defined(STM32F7) -#define RCC_SDIOCLKSOURCE_CLK48 RCC_SDMMC1CLKSOURCE_CLK48 -#define RCC_SDIOCLKSOURCE_SYSCLK RCC_SDMMC1CLKSOURCE_SYSCLK -#endif - -#if defined(STM32H7) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() __HAL_RCC_USB1_OTG_HS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() __HAL_RCC_USB1_OTG_HS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_DISABLE() - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() __HAL_RCC_USB2_OTG_FS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() __HAL_RCC_USB2_OTG_FS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_DISABLE() -#endif - -#define __HAL_RCC_I2SCLK __HAL_RCC_I2S_CONFIG -#define __HAL_RCC_I2SCLK_CONFIG __HAL_RCC_I2S_CONFIG - -#define __RCC_PLLSRC RCC_GET_PLL_OSCSOURCE - -#define IS_RCC_MSIRANGE IS_RCC_MSI_CLOCK_RANGE -#define IS_RCC_RTCCLK_SOURCE IS_RCC_RTCCLKSOURCE -#define IS_RCC_SYSCLK_DIV IS_RCC_HCLK -#define IS_RCC_HCLK_DIV IS_RCC_PCLK -#define IS_RCC_PERIPHCLK IS_RCC_PERIPHCLOCK - -#define RCC_IT_HSI14 RCC_IT_HSI14RDY - -#define RCC_IT_CSSLSE RCC_IT_LSECSS -#define RCC_IT_CSSHSE RCC_IT_CSS - -#define RCC_PLLMUL_3 RCC_PLL_MUL3 -#define RCC_PLLMUL_4 RCC_PLL_MUL4 -#define RCC_PLLMUL_6 RCC_PLL_MUL6 -#define RCC_PLLMUL_8 RCC_PLL_MUL8 -#define RCC_PLLMUL_12 RCC_PLL_MUL12 -#define RCC_PLLMUL_16 RCC_PLL_MUL16 -#define RCC_PLLMUL_24 RCC_PLL_MUL24 -#define RCC_PLLMUL_32 RCC_PLL_MUL32 -#define RCC_PLLMUL_48 RCC_PLL_MUL48 - -#define RCC_PLLDIV_2 RCC_PLL_DIV2 -#define RCC_PLLDIV_3 RCC_PLL_DIV3 -#define RCC_PLLDIV_4 RCC_PLL_DIV4 - -#define IS_RCC_MCOSOURCE IS_RCC_MCO1SOURCE -#define __HAL_RCC_MCO_CONFIG __HAL_RCC_MCO1_CONFIG -#define RCC_MCO_NODIV RCC_MCODIV_1 -#define RCC_MCO_DIV1 RCC_MCODIV_1 -#define RCC_MCO_DIV2 RCC_MCODIV_2 -#define RCC_MCO_DIV4 RCC_MCODIV_4 -#define RCC_MCO_DIV8 RCC_MCODIV_8 -#define RCC_MCO_DIV16 RCC_MCODIV_16 -#define RCC_MCO_DIV32 RCC_MCODIV_32 -#define RCC_MCO_DIV64 RCC_MCODIV_64 -#define RCC_MCO_DIV128 RCC_MCODIV_128 -#define RCC_MCOSOURCE_NONE RCC_MCO1SOURCE_NOCLOCK -#define RCC_MCOSOURCE_LSI RCC_MCO1SOURCE_LSI -#define RCC_MCOSOURCE_LSE RCC_MCO1SOURCE_LSE -#define RCC_MCOSOURCE_SYSCLK RCC_MCO1SOURCE_SYSCLK -#define RCC_MCOSOURCE_HSI RCC_MCO1SOURCE_HSI -#define RCC_MCOSOURCE_HSI14 RCC_MCO1SOURCE_HSI14 -#define RCC_MCOSOURCE_HSI48 RCC_MCO1SOURCE_HSI48 -#define RCC_MCOSOURCE_HSE RCC_MCO1SOURCE_HSE -#define RCC_MCOSOURCE_PLLCLK_DIV1 RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2 - -#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || defined(STM32WL) || defined(STM32C0) -#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE -#else -#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK -#endif - -#define RCC_USBCLK_PLLSAI1 RCC_USBCLKSOURCE_PLLSAI1 -#define RCC_USBCLK_PLL RCC_USBCLKSOURCE_PLL -#define RCC_USBCLK_MSI RCC_USBCLKSOURCE_MSI -#define RCC_USBCLKSOURCE_PLLCLK RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1 RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1_5 RCC_USBCLKSOURCE_PLL_DIV1_5 -#define RCC_USBPLLCLK_DIV2 RCC_USBCLKSOURCE_PLL_DIV2 -#define RCC_USBPLLCLK_DIV3 RCC_USBCLKSOURCE_PLL_DIV3 - -#define HSION_BitNumber RCC_HSION_BIT_NUMBER -#define HSION_BITNUMBER RCC_HSION_BIT_NUMBER -#define HSEON_BitNumber RCC_HSEON_BIT_NUMBER -#define HSEON_BITNUMBER RCC_HSEON_BIT_NUMBER -#define MSION_BITNUMBER RCC_MSION_BIT_NUMBER -#define CSSON_BitNumber RCC_CSSON_BIT_NUMBER -#define CSSON_BITNUMBER RCC_CSSON_BIT_NUMBER -#define PLLON_BitNumber RCC_PLLON_BIT_NUMBER -#define PLLON_BITNUMBER RCC_PLLON_BIT_NUMBER -#define PLLI2SON_BitNumber RCC_PLLI2SON_BIT_NUMBER -#define I2SSRC_BitNumber RCC_I2SSRC_BIT_NUMBER -#define RTCEN_BitNumber RCC_RTCEN_BIT_NUMBER -#define RTCEN_BITNUMBER RCC_RTCEN_BIT_NUMBER -#define BDRST_BitNumber RCC_BDRST_BIT_NUMBER -#define BDRST_BITNUMBER RCC_BDRST_BIT_NUMBER -#define RTCRST_BITNUMBER RCC_RTCRST_BIT_NUMBER -#define LSION_BitNumber RCC_LSION_BIT_NUMBER -#define LSION_BITNUMBER RCC_LSION_BIT_NUMBER -#define LSEON_BitNumber RCC_LSEON_BIT_NUMBER -#define LSEON_BITNUMBER RCC_LSEON_BIT_NUMBER -#define LSEBYP_BITNUMBER RCC_LSEBYP_BIT_NUMBER -#define PLLSAION_BitNumber RCC_PLLSAION_BIT_NUMBER -#define TIMPRE_BitNumber RCC_TIMPRE_BIT_NUMBER -#define RMVF_BitNumber RCC_RMVF_BIT_NUMBER -#define RMVF_BITNUMBER RCC_RMVF_BIT_NUMBER -#define RCC_CR2_HSI14TRIM_BitNumber RCC_HSI14TRIM_BIT_NUMBER -#define CR_BYTE2_ADDRESS RCC_CR_BYTE2_ADDRESS -#define CIR_BYTE1_ADDRESS RCC_CIR_BYTE1_ADDRESS -#define CIR_BYTE2_ADDRESS RCC_CIR_BYTE2_ADDRESS -#define BDCR_BYTE0_ADDRESS RCC_BDCR_BYTE0_ADDRESS -#define DBP_TIMEOUT_VALUE RCC_DBP_TIMEOUT_VALUE -#define LSE_TIMEOUT_VALUE RCC_LSE_TIMEOUT_VALUE - -#define CR_HSION_BB RCC_CR_HSION_BB -#define CR_CSSON_BB RCC_CR_CSSON_BB -#define CR_PLLON_BB RCC_CR_PLLON_BB -#define CR_PLLI2SON_BB RCC_CR_PLLI2SON_BB -#define CR_MSION_BB RCC_CR_MSION_BB -#define CSR_LSION_BB RCC_CSR_LSION_BB -#define CSR_LSEON_BB RCC_CSR_LSEON_BB -#define CSR_LSEBYP_BB RCC_CSR_LSEBYP_BB -#define CSR_RTCEN_BB RCC_CSR_RTCEN_BB -#define CSR_RTCRST_BB RCC_CSR_RTCRST_BB -#define CFGR_I2SSRC_BB RCC_CFGR_I2SSRC_BB -#define BDCR_RTCEN_BB RCC_BDCR_RTCEN_BB -#define BDCR_BDRST_BB RCC_BDCR_BDRST_BB -#define CR_HSEON_BB RCC_CR_HSEON_BB -#define CSR_RMVF_BB RCC_CSR_RMVF_BB -#define CR_PLLSAION_BB RCC_CR_PLLSAION_BB -#define DCKCFGR_TIMPRE_BB RCC_DCKCFGR_TIMPRE_BB - -#define __HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE -#define __HAL_RCC_CRS_DISABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE -#define __HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE -#define __HAL_RCC_CRS_DISABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE -#define __HAL_RCC_CRS_CALCULATE_RELOADVALUE __HAL_RCC_CRS_RELOADVALUE_CALCULATE - -#define __HAL_RCC_GET_IT_SOURCE __HAL_RCC_GET_IT - -#define RCC_CRS_SYNCWARM RCC_CRS_SYNCWARN -#define RCC_CRS_TRIMOV RCC_CRS_TRIMOVF - -#define RCC_PERIPHCLK_CK48 RCC_PERIPHCLK_CLK48 -#define RCC_CK48CLKSOURCE_PLLQ RCC_CLK48CLKSOURCE_PLLQ -#define RCC_CK48CLKSOURCE_PLLSAIP RCC_CLK48CLKSOURCE_PLLSAIP -#define RCC_CK48CLKSOURCE_PLLI2SQ RCC_CLK48CLKSOURCE_PLLI2SQ -#define IS_RCC_CK48CLKSOURCE IS_RCC_CLK48CLKSOURCE -#define RCC_SDIOCLKSOURCE_CK48 RCC_SDIOCLKSOURCE_CLK48 - -#define __HAL_RCC_DFSDM_CLK_ENABLE __HAL_RCC_DFSDM1_CLK_ENABLE -#define __HAL_RCC_DFSDM_CLK_DISABLE __HAL_RCC_DFSDM1_CLK_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_ENABLED __HAL_RCC_DFSDM1_IS_CLK_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_DISABLED __HAL_RCC_DFSDM1_IS_CLK_DISABLED -#define __HAL_RCC_DFSDM_FORCE_RESET __HAL_RCC_DFSDM1_FORCE_RESET -#define __HAL_RCC_DFSDM_RELEASE_RESET __HAL_RCC_DFSDM1_RELEASE_RESET -#define __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE -#define __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_ENABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_DISABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_DISABLED -#define DfsdmClockSelection Dfsdm1ClockSelection -#define RCC_PERIPHCLK_DFSDM RCC_PERIPHCLK_DFSDM1 -#define RCC_DFSDMCLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDMCLKSOURCE_SYSCLK RCC_DFSDM1CLKSOURCE_SYSCLK -#define __HAL_RCC_DFSDM_CONFIG __HAL_RCC_DFSDM1_CONFIG -#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE -#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1 -#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1 -#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1 - -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM2AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM2AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM1CLKSOURCE_APB2 RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDM2CLKSOURCE_APB2 RCC_DFSDM2CLKSOURCE_PCLK2 -#define RCC_FMPI2C1CLKSOURCE_APB RCC_FMPI2C1CLKSOURCE_PCLK1 -#if defined(STM32U5) -#define MSIKPLLModeSEL RCC_MSIKPLL_MODE_SEL -#define MSISPLLModeSEL RCC_MSISPLL_MODE_SEL -#define __HAL_RCC_AHB21_CLK_DISABLE __HAL_RCC_AHB2_1_CLK_DISABLE -#define __HAL_RCC_AHB22_CLK_DISABLE __HAL_RCC_AHB2_2_CLK_DISABLE -#define __HAL_RCC_AHB1_CLK_Disable_Clear __HAL_RCC_AHB1_CLK_ENABLE -#define __HAL_RCC_AHB21_CLK_Disable_Clear __HAL_RCC_AHB2_1_CLK_ENABLE -#define __HAL_RCC_AHB22_CLK_Disable_Clear __HAL_RCC_AHB2_2_CLK_ENABLE -#define __HAL_RCC_AHB3_CLK_Disable_Clear __HAL_RCC_AHB3_CLK_ENABLE -#define __HAL_RCC_APB1_CLK_Disable_Clear __HAL_RCC_APB1_CLK_ENABLE -#define __HAL_RCC_APB2_CLK_Disable_Clear __HAL_RCC_APB2_CLK_ENABLE -#define __HAL_RCC_APB3_CLK_Disable_Clear __HAL_RCC_APB3_CLK_ENABLE -#define IS_RCC_MSIPLLModeSelection IS_RCC_MSIPLLMODE_SELECT -#define RCC_PERIPHCLK_CLK48 RCC_PERIPHCLK_ICLK -#define RCC_CLK48CLKSOURCE_HSI48 RCC_ICLK_CLKSOURCE_HSI48 -#define RCC_CLK48CLKSOURCE_PLL2 RCC_ICLK_CLKSOURCE_PLL2 -#define RCC_CLK48CLKSOURCE_PLL1 RCC_ICLK_CLKSOURCE_PLL1 -#define RCC_CLK48CLKSOURCE_MSIK RCC_ICLK_CLKSOURCE_MSIK -#define __HAL_RCC_ADC1_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE -#define __HAL_RCC_ADC1_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE -#define __HAL_RCC_ADC1_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED -#define __HAL_RCC_ADC1_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED -#define __HAL_RCC_ADC1_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET -#define __HAL_RCC_ADC1_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET -#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC12_CLK_SLEEP_ENABLE -#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC12_CLK_SLEEP_DISABLE -#define __HAL_RCC_GET_CLK48_SOURCE __HAL_RCC_GET_ICLK_SOURCE -#define __HAL_RCC_PLLFRACN_ENABLE __HAL_RCC_PLL_FRACN_ENABLE -#define __HAL_RCC_PLLFRACN_DISABLE __HAL_RCC_PLL_FRACN_DISABLE -#define __HAL_RCC_PLLFRACN_CONFIG __HAL_RCC_PLL_FRACN_CONFIG -#define IS_RCC_PLLFRACN_VALUE IS_RCC_PLL_FRACN_VALUE -#endif /* STM32U5 */ - -/** - * @} - */ - -/** @defgroup HAL_RNG_Aliased_Macros HAL RNG Aliased Macros maintained for legacy purpose - * @{ - */ -#define HAL_RNG_ReadyCallback(__HANDLE__) HAL_RNG_ReadyDataCallback((__HANDLE__), uint32_t random32bit) - -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Macros HAL RTC Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || defined (STM32L4P5xx)|| \ - defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) || \ - defined (STM32C0) -#else -#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG -#endif -#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT -#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT - -#if defined (STM32F1) -#define __HAL_RTC_EXTI_CLEAR_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() - -#define __HAL_RTC_EXTI_ENABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_ENABLE_IT() - -#define __HAL_RTC_EXTI_DISABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_DISABLE_IT() - -#define __HAL_RTC_EXTI_GET_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GET_FLAG() - -#define __HAL_RTC_EXTI_GENERATE_SWIT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() -#else -#define __HAL_RTC_EXTI_CLEAR_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG())) -#define __HAL_RTC_EXTI_ENABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_ENABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT())) -#define __HAL_RTC_EXTI_DISABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_DISABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT())) -#define __HAL_RTC_EXTI_GET_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GET_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG())) -#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT())) -#endif /* STM32F1 */ - -#define IS_ALARM IS_RTC_ALARM -#define IS_ALARM_MASK IS_RTC_ALARM_MASK -#define IS_TAMPER IS_RTC_TAMPER -#define IS_TAMPER_ERASE_MODE IS_RTC_TAMPER_ERASE_MODE -#define IS_TAMPER_FILTER IS_RTC_TAMPER_FILTER -#define IS_TAMPER_INTERRUPT IS_RTC_TAMPER_INTERRUPT -#define IS_TAMPER_MASKFLAG_STATE IS_RTC_TAMPER_MASKFLAG_STATE -#define IS_TAMPER_PRECHARGE_DURATION IS_RTC_TAMPER_PRECHARGE_DURATION -#define IS_TAMPER_PULLUP_STATE IS_RTC_TAMPER_PULLUP_STATE -#define IS_TAMPER_SAMPLING_FREQ IS_RTC_TAMPER_SAMPLING_FREQ -#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION -#define IS_TAMPER_TRIGGER IS_RTC_TAMPER_TRIGGER -#define IS_WAKEUP_CLOCK IS_RTC_WAKEUP_CLOCK -#define IS_WAKEUP_COUNTER IS_RTC_WAKEUP_COUNTER - -#define __RTC_WRITEPROTECTION_ENABLE __HAL_RTC_WRITEPROTECTION_ENABLE -#define __RTC_WRITEPROTECTION_DISABLE __HAL_RTC_WRITEPROTECTION_DISABLE - -/** - * @} - */ - -/** @defgroup HAL_SD_Aliased_Macros HAL SD/MMC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define SD_OCR_CID_CSD_OVERWRIETE SD_OCR_CID_CSD_OVERWRITE -#define SD_CMD_SD_APP_STAUS SD_CMD_SD_APP_STATUS - -#if !defined(STM32F1) && !defined(STM32F2) && !defined(STM32F4) && !defined(STM32L1) -#define eMMC_HIGH_VOLTAGE_RANGE EMMC_HIGH_VOLTAGE_RANGE -#define eMMC_DUAL_VOLTAGE_RANGE EMMC_DUAL_VOLTAGE_RANGE -#define eMMC_LOW_VOLTAGE_RANGE EMMC_LOW_VOLTAGE_RANGE - -#define SDMMC_NSpeed_CLK_DIV SDMMC_NSPEED_CLK_DIV -#define SDMMC_HSpeed_CLK_DIV SDMMC_HSPEED_CLK_DIV -#endif - -#if defined(STM32F4) || defined(STM32F2) -#define SD_SDMMC_DISABLED SD_SDIO_DISABLED -#define SD_SDMMC_FUNCTION_BUSY SD_SDIO_FUNCTION_BUSY -#define SD_SDMMC_FUNCTION_FAILED SD_SDIO_FUNCTION_FAILED -#define SD_SDMMC_UNKNOWN_FUNCTION SD_SDIO_UNKNOWN_FUNCTION -#define SD_CMD_SDMMC_SEN_OP_COND SD_CMD_SDIO_SEN_OP_COND -#define SD_CMD_SDMMC_RW_DIRECT SD_CMD_SDIO_RW_DIRECT -#define SD_CMD_SDMMC_RW_EXTENDED SD_CMD_SDIO_RW_EXTENDED -#define __HAL_SD_SDMMC_ENABLE __HAL_SD_SDIO_ENABLE -#define __HAL_SD_SDMMC_DISABLE __HAL_SD_SDIO_DISABLE -#define __HAL_SD_SDMMC_DMA_ENABLE __HAL_SD_SDIO_DMA_ENABLE -#define __HAL_SD_SDMMC_DMA_DISABLE __HAL_SD_SDIO_DMA_DISABL -#define __HAL_SD_SDMMC_ENABLE_IT __HAL_SD_SDIO_ENABLE_IT -#define __HAL_SD_SDMMC_DISABLE_IT __HAL_SD_SDIO_DISABLE_IT -#define __HAL_SD_SDMMC_GET_FLAG __HAL_SD_SDIO_GET_FLAG -#define __HAL_SD_SDMMC_CLEAR_FLAG __HAL_SD_SDIO_CLEAR_FLAG -#define __HAL_SD_SDMMC_GET_IT __HAL_SD_SDIO_GET_IT -#define __HAL_SD_SDMMC_CLEAR_IT __HAL_SD_SDIO_CLEAR_IT -#define SDMMC_STATIC_FLAGS SDIO_STATIC_FLAGS -#define SDMMC_CMD0TIMEOUT SDIO_CMD0TIMEOUT -#define SD_SDMMC_SEND_IF_COND SD_SDIO_SEND_IF_COND -/* alias CMSIS */ -#define SDMMC1_IRQn SDIO_IRQn -#define SDMMC1_IRQHandler SDIO_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define SD_SDIO_DISABLED SD_SDMMC_DISABLED -#define SD_SDIO_FUNCTION_BUSY SD_SDMMC_FUNCTION_BUSY -#define SD_SDIO_FUNCTION_FAILED SD_SDMMC_FUNCTION_FAILED -#define SD_SDIO_UNKNOWN_FUNCTION SD_SDMMC_UNKNOWN_FUNCTION -#define SD_CMD_SDIO_SEN_OP_COND SD_CMD_SDMMC_SEN_OP_COND -#define SD_CMD_SDIO_RW_DIRECT SD_CMD_SDMMC_RW_DIRECT -#define SD_CMD_SDIO_RW_EXTENDED SD_CMD_SDMMC_RW_EXTENDED -#define __HAL_SD_SDIO_ENABLE __HAL_SD_SDMMC_ENABLE -#define __HAL_SD_SDIO_DISABLE __HAL_SD_SDMMC_DISABLE -#define __HAL_SD_SDIO_DMA_ENABLE __HAL_SD_SDMMC_DMA_ENABLE -#define __HAL_SD_SDIO_DMA_DISABL __HAL_SD_SDMMC_DMA_DISABLE -#define __HAL_SD_SDIO_ENABLE_IT __HAL_SD_SDMMC_ENABLE_IT -#define __HAL_SD_SDIO_DISABLE_IT __HAL_SD_SDMMC_DISABLE_IT -#define __HAL_SD_SDIO_GET_FLAG __HAL_SD_SDMMC_GET_FLAG -#define __HAL_SD_SDIO_CLEAR_FLAG __HAL_SD_SDMMC_CLEAR_FLAG -#define __HAL_SD_SDIO_GET_IT __HAL_SD_SDMMC_GET_IT -#define __HAL_SD_SDIO_CLEAR_IT __HAL_SD_SDMMC_CLEAR_IT -#define SDIO_STATIC_FLAGS SDMMC_STATIC_FLAGS -#define SDIO_CMD0TIMEOUT SDMMC_CMD0TIMEOUT -#define SD_SDIO_SEND_IF_COND SD_SDMMC_SEND_IF_COND -/* alias CMSIS for compatibilities */ -#define SDIO_IRQn SDMMC1_IRQn -#define SDIO_IRQHandler SDMMC1_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32F4) || defined(STM32F2) || defined(STM32L4) || defined(STM32H7) -#define HAL_SD_CardCIDTypedef HAL_SD_CardCIDTypeDef -#define HAL_SD_CardCSDTypedef HAL_SD_CardCSDTypeDef -#define HAL_SD_CardStatusTypedef HAL_SD_CardStatusTypeDef -#define HAL_SD_CardStateTypedef HAL_SD_CardStateTypeDef -#endif - -#if defined(STM32H7) || defined(STM32L5) -#define HAL_MMCEx_Read_DMADoubleBuffer0CpltCallback HAL_MMCEx_Read_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Read_DMADoubleBuffer1CpltCallback HAL_MMCEx_Read_DMADoubleBuf1CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer0CpltCallback HAL_MMCEx_Write_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer1CpltCallback HAL_MMCEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer0CpltCallback HAL_SDEx_Read_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer1CpltCallback HAL_SDEx_Read_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer0CpltCallback HAL_SDEx_Write_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer1CpltCallback HAL_SDEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SD_DriveTransciver_1_8V_Callback HAL_SD_DriveTransceiver_1_8V_Callback -#endif -/** - * @} - */ - -/** @defgroup HAL_SMARTCARD_Aliased_Macros HAL SMARTCARD Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __SMARTCARD_ENABLE_IT __HAL_SMARTCARD_ENABLE_IT -#define __SMARTCARD_DISABLE_IT __HAL_SMARTCARD_DISABLE_IT -#define __SMARTCARD_ENABLE __HAL_SMARTCARD_ENABLE -#define __SMARTCARD_DISABLE __HAL_SMARTCARD_DISABLE -#define __SMARTCARD_DMA_REQUEST_ENABLE __HAL_SMARTCARD_DMA_REQUEST_ENABLE -#define __SMARTCARD_DMA_REQUEST_DISABLE __HAL_SMARTCARD_DMA_REQUEST_DISABLE - -#define __HAL_SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE -#define __SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE - -#define IS_SMARTCARD_ONEBIT_SAMPLING IS_SMARTCARD_ONE_BIT_SAMPLE - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Macros HAL SMBUS Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_SMBUS_RESET_CR1 SMBUS_RESET_CR1 -#define __HAL_SMBUS_RESET_CR2 SMBUS_RESET_CR2 -#define __HAL_SMBUS_GENERATE_START SMBUS_GENERATE_START -#define __HAL_SMBUS_GET_ADDR_MATCH SMBUS_GET_ADDR_MATCH -#define __HAL_SMBUS_GET_DIR SMBUS_GET_DIR -#define __HAL_SMBUS_GET_STOP_MODE SMBUS_GET_STOP_MODE -#define __HAL_SMBUS_GET_PEC_MODE SMBUS_GET_PEC_MODE -#define __HAL_SMBUS_GET_ALERT_ENABLED SMBUS_GET_ALERT_ENABLED -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Macros HAL SPI Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_SPI_1LINE_TX SPI_1LINE_TX -#define __HAL_SPI_1LINE_RX SPI_1LINE_RX -#define __HAL_SPI_RESET_CRC SPI_RESET_CRC - -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Macros HAL UART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __HAL_UART_MASK_COMPUTATION UART_MASK_COMPUTATION -#define __UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __UART_MASK_COMPUTATION UART_MASK_COMPUTATION - -#define IS_UART_WAKEUPMETHODE IS_UART_WAKEUPMETHOD - -#define IS_UART_ONEBIT_SAMPLE IS_UART_ONE_BIT_SAMPLE -#define IS_UART_ONEBIT_SAMPLING IS_UART_ONE_BIT_SAMPLE - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Macros HAL USART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __USART_ENABLE_IT __HAL_USART_ENABLE_IT -#define __USART_DISABLE_IT __HAL_USART_DISABLE_IT -#define __USART_ENABLE __HAL_USART_ENABLE -#define __USART_DISABLE __HAL_USART_DISABLE - -#define __HAL_USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE -#define __USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F7) -#define USART_OVERSAMPLING_16 0x00000000U -#define USART_OVERSAMPLING_8 USART_CR1_OVER8 - -#define IS_USART_OVERSAMPLING(__SAMPLING__) (((__SAMPLING__) == USART_OVERSAMPLING_16) || \ - ((__SAMPLING__) == USART_OVERSAMPLING_8)) -#endif /* STM32F0 || STM32F3 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_USB_Aliased_Macros HAL USB Aliased Macros maintained for legacy purpose - * @{ - */ -#define USB_EXTI_LINE_WAKEUP USB_WAKEUP_EXTI_LINE - -#define USB_FS_EXTI_TRIGGER_RISING_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_EDGE -#define USB_FS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_FS_WAKEUP_EXTI_FALLING_EDGE -#define USB_FS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_FS_EXTI_LINE_WAKEUP USB_OTG_FS_WAKEUP_EXTI_LINE - -#define USB_HS_EXTI_TRIGGER_RISING_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_EDGE -#define USB_HS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_HS_WAKEUP_EXTI_FALLING_EDGE -#define USB_HS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_HS_EXTI_LINE_WAKEUP USB_OTG_HS_WAKEUP_EXTI_LINE - -#define __HAL_USB_EXTI_ENABLE_IT __HAL_USB_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_EXTI_DISABLE_IT __HAL_USB_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_EXTI_GET_FLAG __HAL_USB_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_EXTI_CLEAR_FLAG __HAL_USB_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_EXTI_SET_RISING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_EXTI_SET_FALLING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE - -#define __HAL_USB_FS_EXTI_ENABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_FS_EXTI_DISABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_FS_EXTI_GET_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_FS_EXTI_CLEAR_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_FS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_FS_EXTI_GENERATE_SWIT __HAL_USB_OTG_FS_WAKEUP_EXTI_GENERATE_SWIT - -#define __HAL_USB_HS_EXTI_ENABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_HS_EXTI_DISABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_HS_EXTI_GET_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_HS_EXTI_CLEAR_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_HS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_HS_EXTI_GENERATE_SWIT __HAL_USB_OTG_HS_WAKEUP_EXTI_GENERATE_SWIT - -#define HAL_PCD_ActiveRemoteWakeup HAL_PCD_ActivateRemoteWakeup -#define HAL_PCD_DeActiveRemoteWakeup HAL_PCD_DeActivateRemoteWakeup - -#define HAL_PCD_SetTxFiFo HAL_PCDEx_SetTxFiFo -#define HAL_PCD_SetRxFiFo HAL_PCDEx_SetRxFiFo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Macros HAL TIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_TIM_SetICPrescalerValue TIM_SET_ICPRESCALERVALUE -#define __HAL_TIM_ResetICPrescalerValue TIM_RESET_ICPRESCALERVALUE - -#define TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE -#define TIM_GET_CLEAR_IT __HAL_TIM_CLEAR_IT - -#define __HAL_TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE - -#define __HAL_TIM_DIRECTION_STATUS __HAL_TIM_IS_TIM_COUNTING_DOWN -#define __HAL_TIM_PRESCALER __HAL_TIM_SET_PRESCALER -#define __HAL_TIM_SetCounter __HAL_TIM_SET_COUNTER -#define __HAL_TIM_GetCounter __HAL_TIM_GET_COUNTER -#define __HAL_TIM_SetAutoreload __HAL_TIM_SET_AUTORELOAD -#define __HAL_TIM_GetAutoreload __HAL_TIM_GET_AUTORELOAD -#define __HAL_TIM_SetClockDivision __HAL_TIM_SET_CLOCKDIVISION -#define __HAL_TIM_GetClockDivision __HAL_TIM_GET_CLOCKDIVISION -#define __HAL_TIM_SetICPrescaler __HAL_TIM_SET_ICPRESCALER -#define __HAL_TIM_GetICPrescaler __HAL_TIM_GET_ICPRESCALER -#define __HAL_TIM_SetCompare __HAL_TIM_SET_COMPARE -#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE - -#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1 -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Macros HAL ETH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_ETH_EXTI_ENABLE_IT __HAL_ETH_WAKEUP_EXTI_ENABLE_IT -#define __HAL_ETH_EXTI_DISABLE_IT __HAL_ETH_WAKEUP_EXTI_DISABLE_IT -#define __HAL_ETH_EXTI_GET_FLAG __HAL_ETH_WAKEUP_EXTI_GET_FLAG -#define __HAL_ETH_EXTI_CLEAR_FLAG __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_ETH_EXTI_SET_RISING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLINGRISING_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER - -#define ETH_PROMISCIOUSMODE_ENABLE ETH_PROMISCUOUS_MODE_ENABLE -#define ETH_PROMISCIOUSMODE_DISABLE ETH_PROMISCUOUS_MODE_DISABLE -#define IS_ETH_PROMISCIOUS_MODE IS_ETH_PROMISCUOUS_MODE -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Macros HAL LTDC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_LTDC_LAYER LTDC_LAYER -#define __HAL_LTDC_RELOAD_CONFIG __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG -/** - * @} - */ - -/** @defgroup HAL_SAI_Aliased_Macros HAL SAI Aliased Macros maintained for legacy purpose - * @{ - */ -#define SAI_OUTPUTDRIVE_DISABLED SAI_OUTPUTDRIVE_DISABLE -#define SAI_OUTPUTDRIVE_ENABLED SAI_OUTPUTDRIVE_ENABLE -#define SAI_MASTERDIVIDER_ENABLED SAI_MASTERDIVIDER_ENABLE -#define SAI_MASTERDIVIDER_DISABLED SAI_MASTERDIVIDER_DISABLE -#define SAI_STREOMODE SAI_STEREOMODE -#define SAI_FIFOStatus_Empty SAI_FIFOSTATUS_EMPTY -#define SAI_FIFOStatus_Less1QuarterFull SAI_FIFOSTATUS_LESS1QUARTERFULL -#define SAI_FIFOStatus_1QuarterFull SAI_FIFOSTATUS_1QUARTERFULL -#define SAI_FIFOStatus_HalfFull SAI_FIFOSTATUS_HALFFULL -#define SAI_FIFOStatus_3QuartersFull SAI_FIFOSTATUS_3QUARTERFULL -#define SAI_FIFOStatus_Full SAI_FIFOSTATUS_FULL -#define IS_SAI_BLOCK_MONO_STREO_MODE IS_SAI_BLOCK_MONO_STEREO_MODE -#define SAI_SYNCHRONOUS_EXT SAI_SYNCHRONOUS_EXT_SAI1 -#define SAI_SYNCEXT_IN_ENABLE SAI_SYNCEXT_OUTBLOCKA_ENABLE -/** - * @} - */ - -/** @defgroup HAL_SPDIFRX_Aliased_Macros HAL SPDIFRX Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32H7) -#define HAL_SPDIFRX_ReceiveControlFlow HAL_SPDIFRX_ReceiveCtrlFlow -#define HAL_SPDIFRX_ReceiveControlFlow_IT HAL_SPDIFRX_ReceiveCtrlFlow_IT -#define HAL_SPDIFRX_ReceiveControlFlow_DMA HAL_SPDIFRX_ReceiveCtrlFlow_DMA -#endif -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Functions HAL HRTIM Aliased Functions maintained for legacy purpose - * @{ - */ -#if defined (STM32H7) || defined (STM32G4) || defined (STM32F3) -#define HAL_HRTIM_WaveformCounterStart_IT HAL_HRTIM_WaveformCountStart_IT -#define HAL_HRTIM_WaveformCounterStart_DMA HAL_HRTIM_WaveformCountStart_DMA -#define HAL_HRTIM_WaveformCounterStart HAL_HRTIM_WaveformCountStart -#define HAL_HRTIM_WaveformCounterStop_IT HAL_HRTIM_WaveformCountStop_IT -#define HAL_HRTIM_WaveformCounterStop_DMA HAL_HRTIM_WaveformCountStop_DMA -#define HAL_HRTIM_WaveformCounterStop HAL_HRTIM_WaveformCountStop -#endif -/** - * @} - */ - -/** @defgroup HAL_QSPI_Aliased_Macros HAL QSPI Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32L4) || defined (STM32F4) || defined (STM32F7) || defined(STM32H7) -#define HAL_QPSI_TIMEOUT_DEFAULT_VALUE HAL_QSPI_TIMEOUT_DEFAULT_VALUE -#endif /* STM32L4 || STM32F4 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_Generic_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32F7) -#define ART_ACCLERATOR_ENABLE ART_ACCELERATOR_ENABLE -#endif /* STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_PPP_Aliased_Macros HAL PPP Aliased Macros maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32_HAL_LEGACY */ - - +/** + ****************************************************************************** + * @file stm32_hal_legacy.h + * @author MCD Application Team + * @brief This file contains aliases definition for the STM32Cube HAL constants + * macros and functions maintained for legacy purpose. + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32_HAL_LEGACY +#define STM32_HAL_LEGACY + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup HAL_AES_Aliased_Defines HAL CRYP Aliased Defines maintained for legacy purpose + * @{ + */ +#define AES_FLAG_RDERR CRYP_FLAG_RDERR +#define AES_FLAG_WRERR CRYP_FLAG_WRERR +#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF +#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR +#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR +#if defined(STM32U5) || defined(STM32H7) || defined(STM32MP1) +#define CRYP_DATATYPE_32B CRYP_NO_SWAP +#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP +#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP +#define CRYP_DATATYPE_1B CRYP_BIT_SWAP +#if defined(STM32U5) +#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF +#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF +#endif /* STM32U5 */ +#endif /* STM32U5 || STM32H7 || STM32MP1 */ +/** + * @} + */ + +/** @defgroup HAL_ADC_Aliased_Defines HAL ADC Aliased Defines maintained for legacy purpose + * @{ + */ +#define ADC_RESOLUTION12b ADC_RESOLUTION_12B +#define ADC_RESOLUTION10b ADC_RESOLUTION_10B +#define ADC_RESOLUTION8b ADC_RESOLUTION_8B +#define ADC_RESOLUTION6b ADC_RESOLUTION_6B +#define OVR_DATA_OVERWRITTEN ADC_OVR_DATA_OVERWRITTEN +#define OVR_DATA_PRESERVED ADC_OVR_DATA_PRESERVED +#define EOC_SINGLE_CONV ADC_EOC_SINGLE_CONV +#define EOC_SEQ_CONV ADC_EOC_SEQ_CONV +#define EOC_SINGLE_SEQ_CONV ADC_EOC_SINGLE_SEQ_CONV +#define REGULAR_GROUP ADC_REGULAR_GROUP +#define INJECTED_GROUP ADC_INJECTED_GROUP +#define REGULAR_INJECTED_GROUP ADC_REGULAR_INJECTED_GROUP +#define AWD_EVENT ADC_AWD_EVENT +#define AWD1_EVENT ADC_AWD1_EVENT +#define AWD2_EVENT ADC_AWD2_EVENT +#define AWD3_EVENT ADC_AWD3_EVENT +#define OVR_EVENT ADC_OVR_EVENT +#define JQOVF_EVENT ADC_JQOVF_EVENT +#define ALL_CHANNELS ADC_ALL_CHANNELS +#define REGULAR_CHANNELS ADC_REGULAR_CHANNELS +#define INJECTED_CHANNELS ADC_INJECTED_CHANNELS +#define SYSCFG_FLAG_SENSOR_ADC ADC_FLAG_SENSOR +#define SYSCFG_FLAG_VREF_ADC ADC_FLAG_VREFINT +#define ADC_CLOCKPRESCALER_PCLK_DIV1 ADC_CLOCK_SYNC_PCLK_DIV1 +#define ADC_CLOCKPRESCALER_PCLK_DIV2 ADC_CLOCK_SYNC_PCLK_DIV2 +#define ADC_CLOCKPRESCALER_PCLK_DIV4 ADC_CLOCK_SYNC_PCLK_DIV4 +#define ADC_CLOCKPRESCALER_PCLK_DIV6 ADC_CLOCK_SYNC_PCLK_DIV6 +#define ADC_CLOCKPRESCALER_PCLK_DIV8 ADC_CLOCK_SYNC_PCLK_DIV8 +#define ADC_EXTERNALTRIG0_T6_TRGO ADC_EXTERNALTRIGCONV_T6_TRGO +#define ADC_EXTERNALTRIG1_T21_CC2 ADC_EXTERNALTRIGCONV_T21_CC2 +#define ADC_EXTERNALTRIG2_T2_TRGO ADC_EXTERNALTRIGCONV_T2_TRGO +#define ADC_EXTERNALTRIG3_T2_CC4 ADC_EXTERNALTRIGCONV_T2_CC4 +#define ADC_EXTERNALTRIG4_T22_TRGO ADC_EXTERNALTRIGCONV_T22_TRGO +#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_EXTERNALTRIGCONV_EXT_IT11 +#define ADC_CLOCK_ASYNC ADC_CLOCK_ASYNC_DIV1 +#define ADC_EXTERNALTRIG_EDGE_NONE ADC_EXTERNALTRIGCONVEDGE_NONE +#define ADC_EXTERNALTRIG_EDGE_RISING ADC_EXTERNALTRIGCONVEDGE_RISING +#define ADC_EXTERNALTRIG_EDGE_FALLING ADC_EXTERNALTRIGCONVEDGE_FALLING +#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING +#define ADC_SAMPLETIME_2CYCLE_5 ADC_SAMPLETIME_2CYCLES_5 + +#define HAL_ADC_STATE_BUSY_REG HAL_ADC_STATE_REG_BUSY +#define HAL_ADC_STATE_BUSY_INJ HAL_ADC_STATE_INJ_BUSY +#define HAL_ADC_STATE_EOC_REG HAL_ADC_STATE_REG_EOC +#define HAL_ADC_STATE_EOC_INJ HAL_ADC_STATE_INJ_EOC +#define HAL_ADC_STATE_ERROR HAL_ADC_STATE_ERROR_INTERNAL +#define HAL_ADC_STATE_BUSY HAL_ADC_STATE_BUSY_INTERNAL +#define HAL_ADC_STATE_AWD HAL_ADC_STATE_AWD1 + +#if defined(STM32H7) +#define ADC_CHANNEL_VBAT_DIV4 ADC_CHANNEL_VBAT +#endif /* STM32H7 */ + +#if defined(STM32U5) +#define ADC_SAMPLETIME_5CYCLE ADC_SAMPLETIME_5CYCLES +#define ADC_SAMPLETIME_391CYCLES_5 ADC_SAMPLETIME_391CYCLES +#define ADC4_SAMPLETIME_160CYCLES_5 ADC4_SAMPLETIME_814CYCLES_5 +#endif /* STM32U5 */ + +/** + * @} + */ + +/** @defgroup HAL_CEC_Aliased_Defines HAL CEC Aliased Defines maintained for legacy purpose + * @{ + */ + +#define __HAL_CEC_GET_IT __HAL_CEC_GET_FLAG + +/** + * @} + */ + +/** @defgroup HAL_COMP_Aliased_Defines HAL COMP Aliased Defines maintained for legacy purpose + * @{ + */ +#define COMP_WINDOWMODE_DISABLED COMP_WINDOWMODE_DISABLE +#define COMP_WINDOWMODE_ENABLED COMP_WINDOWMODE_ENABLE +#define COMP_EXTI_LINE_COMP1_EVENT COMP_EXTI_LINE_COMP1 +#define COMP_EXTI_LINE_COMP2_EVENT COMP_EXTI_LINE_COMP2 +#define COMP_EXTI_LINE_COMP3_EVENT COMP_EXTI_LINE_COMP3 +#define COMP_EXTI_LINE_COMP4_EVENT COMP_EXTI_LINE_COMP4 +#define COMP_EXTI_LINE_COMP5_EVENT COMP_EXTI_LINE_COMP5 +#define COMP_EXTI_LINE_COMP6_EVENT COMP_EXTI_LINE_COMP6 +#define COMP_EXTI_LINE_COMP7_EVENT COMP_EXTI_LINE_COMP7 +#if defined(STM32L0) +#define COMP_LPTIMCONNECTION_ENABLED ((uint32_t)0x00000003U) /*!< COMPX output generic naming: connected to LPTIM input 1 for COMP1, LPTIM input 2 for COMP2 */ +#endif +#define COMP_OUTPUT_COMP6TIM2OCREFCLR COMP_OUTPUT_COMP6_TIM2OCREFCLR +#if defined(STM32F373xC) || defined(STM32F378xx) +#define COMP_OUTPUT_TIM3IC1 COMP_OUTPUT_COMP1_TIM3IC1 +#define COMP_OUTPUT_TIM3OCREFCLR COMP_OUTPUT_COMP1_TIM3OCREFCLR +#endif /* STM32F373xC || STM32F378xx */ + +#if defined(STM32L0) || defined(STM32L4) +#define COMP_WINDOWMODE_ENABLE COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON + +#define COMP_NONINVERTINGINPUT_IO1 COMP_INPUT_PLUS_IO1 +#define COMP_NONINVERTINGINPUT_IO2 COMP_INPUT_PLUS_IO2 +#define COMP_NONINVERTINGINPUT_IO3 COMP_INPUT_PLUS_IO3 +#define COMP_NONINVERTINGINPUT_IO4 COMP_INPUT_PLUS_IO4 +#define COMP_NONINVERTINGINPUT_IO5 COMP_INPUT_PLUS_IO5 +#define COMP_NONINVERTINGINPUT_IO6 COMP_INPUT_PLUS_IO6 + +#define COMP_INVERTINGINPUT_1_4VREFINT COMP_INPUT_MINUS_1_4VREFINT +#define COMP_INVERTINGINPUT_1_2VREFINT COMP_INPUT_MINUS_1_2VREFINT +#define COMP_INVERTINGINPUT_3_4VREFINT COMP_INPUT_MINUS_3_4VREFINT +#define COMP_INVERTINGINPUT_VREFINT COMP_INPUT_MINUS_VREFINT +#define COMP_INVERTINGINPUT_DAC1_CH1 COMP_INPUT_MINUS_DAC1_CH1 +#define COMP_INVERTINGINPUT_DAC1_CH2 COMP_INPUT_MINUS_DAC1_CH2 +#define COMP_INVERTINGINPUT_DAC1 COMP_INPUT_MINUS_DAC1_CH1 +#define COMP_INVERTINGINPUT_DAC2 COMP_INPUT_MINUS_DAC1_CH2 +#define COMP_INVERTINGINPUT_IO1 COMP_INPUT_MINUS_IO1 +#if defined(STM32L0) +/* Issue fixed on STM32L0 COMP driver: only 2 dedicated IO (IO1 and IO2), */ +/* IO2 was wrongly assigned to IO shared with DAC and IO3 was corresponding */ +/* to the second dedicated IO (only for COMP2). */ +#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_DAC1_CH2 +#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO2 +#else +#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_IO2 +#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO3 +#endif +#define COMP_INVERTINGINPUT_IO4 COMP_INPUT_MINUS_IO4 +#define COMP_INVERTINGINPUT_IO5 COMP_INPUT_MINUS_IO5 + +#define COMP_OUTPUTLEVEL_LOW COMP_OUTPUT_LEVEL_LOW +#define COMP_OUTPUTLEVEL_HIGH COMP_OUTPUT_LEVEL_HIGH + +/* Note: Literal "COMP_FLAG_LOCK" kept for legacy purpose. */ +/* To check COMP lock state, use macro "__HAL_COMP_IS_LOCKED()". */ +#if defined(COMP_CSR_LOCK) +#define COMP_FLAG_LOCK COMP_CSR_LOCK +#elif defined(COMP_CSR_COMP1LOCK) +#define COMP_FLAG_LOCK COMP_CSR_COMP1LOCK +#elif defined(COMP_CSR_COMPxLOCK) +#define COMP_FLAG_LOCK COMP_CSR_COMPxLOCK +#endif + +#if defined(STM32L4) +#define COMP_BLANKINGSRCE_TIM1OC5 COMP_BLANKINGSRC_TIM1_OC5_COMP1 +#define COMP_BLANKINGSRCE_TIM2OC3 COMP_BLANKINGSRC_TIM2_OC3_COMP1 +#define COMP_BLANKINGSRCE_TIM3OC3 COMP_BLANKINGSRC_TIM3_OC3_COMP1 +#define COMP_BLANKINGSRCE_TIM3OC4 COMP_BLANKINGSRC_TIM3_OC4_COMP2 +#define COMP_BLANKINGSRCE_TIM8OC5 COMP_BLANKINGSRC_TIM8_OC5_COMP2 +#define COMP_BLANKINGSRCE_TIM15OC1 COMP_BLANKINGSRC_TIM15_OC1_COMP2 +#define COMP_BLANKINGSRCE_NONE COMP_BLANKINGSRC_NONE +#endif + +#if defined(STM32L0) +#define COMP_MODE_HIGHSPEED COMP_POWERMODE_MEDIUMSPEED +#define COMP_MODE_LOWSPEED COMP_POWERMODE_ULTRALOWPOWER +#else +#define COMP_MODE_HIGHSPEED COMP_POWERMODE_HIGHSPEED +#define COMP_MODE_MEDIUMSPEED COMP_POWERMODE_MEDIUMSPEED +#define COMP_MODE_LOWPOWER COMP_POWERMODE_LOWPOWER +#define COMP_MODE_ULTRALOWPOWER COMP_POWERMODE_ULTRALOWPOWER +#endif + +#endif +/** + * @} + */ + +/** @defgroup HAL_CORTEX_Aliased_Defines HAL CORTEX Aliased Defines maintained for legacy purpose + * @{ + */ +#define __HAL_CORTEX_SYSTICKCLK_CONFIG HAL_SYSTICK_CLKSourceConfig +#if defined(STM32U5) +#define MPU_DEVICE_nGnRnE MPU_DEVICE_NGNRNE +#define MPU_DEVICE_nGnRE MPU_DEVICE_NGNRE +#define MPU_DEVICE_nGRE MPU_DEVICE_NGRE +#endif /* STM32U5 */ +/** + * @} + */ + +/** @defgroup CRC_Aliases CRC API aliases + * @{ + */ +#if defined(STM32C0) +#else +#define HAL_CRC_Input_Data_Reverse HAL_CRCEx_Input_Data_Reverse /*!< Aliased to HAL_CRCEx_Input_Data_Reverse for inter STM32 series compatibility */ +#define HAL_CRC_Output_Data_Reverse HAL_CRCEx_Output_Data_Reverse /*!< Aliased to HAL_CRCEx_Output_Data_Reverse for inter STM32 series compatibility */ +#endif +/** + * @} + */ + +/** @defgroup HAL_CRC_Aliased_Defines HAL CRC Aliased Defines maintained for legacy purpose + * @{ + */ + +#define CRC_OUTPUTDATA_INVERSION_DISABLED CRC_OUTPUTDATA_INVERSION_DISABLE +#define CRC_OUTPUTDATA_INVERSION_ENABLED CRC_OUTPUTDATA_INVERSION_ENABLE + +/** + * @} + */ + +/** @defgroup HAL_DAC_Aliased_Defines HAL DAC Aliased Defines maintained for legacy purpose + * @{ + */ + +#define DAC1_CHANNEL_1 DAC_CHANNEL_1 +#define DAC1_CHANNEL_2 DAC_CHANNEL_2 +#define DAC2_CHANNEL_1 DAC_CHANNEL_1 +#define DAC_WAVE_NONE 0x00000000U +#define DAC_WAVE_NOISE DAC_CR_WAVE1_0 +#define DAC_WAVE_TRIANGLE DAC_CR_WAVE1_1 +#define DAC_WAVEGENERATION_NONE DAC_WAVE_NONE +#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE +#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE + +#if defined(STM32G4) || defined(STM32H7) || defined (STM32U5) +#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL +#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL +#endif + +#if defined(STM32U5) +#define DAC_TRIGGER_STOP_LPTIM1_OUT DAC_TRIGGER_STOP_LPTIM1_CH1 +#define DAC_TRIGGER_STOP_LPTIM3_OUT DAC_TRIGGER_STOP_LPTIM3_CH1 +#define DAC_TRIGGER_LPTIM1_OUT DAC_TRIGGER_LPTIM1_CH1 +#define DAC_TRIGGER_LPTIM3_OUT DAC_TRIGGER_LPTIM3_CH1 +#endif + +#if defined(STM32L1) || defined(STM32L4) || defined(STM32G0) || defined(STM32L5) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) +#define HAL_DAC_MSP_INIT_CB_ID HAL_DAC_MSPINIT_CB_ID +#define HAL_DAC_MSP_DEINIT_CB_ID HAL_DAC_MSPDEINIT_CB_ID +#endif + +/** + * @} + */ + +/** @defgroup HAL_DMA_Aliased_Defines HAL DMA Aliased Defines maintained for legacy purpose + * @{ + */ +#define HAL_REMAPDMA_ADC_DMA_CH2 DMA_REMAP_ADC_DMA_CH2 +#define HAL_REMAPDMA_USART1_TX_DMA_CH4 DMA_REMAP_USART1_TX_DMA_CH4 +#define HAL_REMAPDMA_USART1_RX_DMA_CH5 DMA_REMAP_USART1_RX_DMA_CH5 +#define HAL_REMAPDMA_TIM16_DMA_CH4 DMA_REMAP_TIM16_DMA_CH4 +#define HAL_REMAPDMA_TIM17_DMA_CH2 DMA_REMAP_TIM17_DMA_CH2 +#define HAL_REMAPDMA_USART3_DMA_CH32 DMA_REMAP_USART3_DMA_CH32 +#define HAL_REMAPDMA_TIM16_DMA_CH6 DMA_REMAP_TIM16_DMA_CH6 +#define HAL_REMAPDMA_TIM17_DMA_CH7 DMA_REMAP_TIM17_DMA_CH7 +#define HAL_REMAPDMA_SPI2_DMA_CH67 DMA_REMAP_SPI2_DMA_CH67 +#define HAL_REMAPDMA_USART2_DMA_CH67 DMA_REMAP_USART2_DMA_CH67 +#define HAL_REMAPDMA_I2C1_DMA_CH76 DMA_REMAP_I2C1_DMA_CH76 +#define HAL_REMAPDMA_TIM1_DMA_CH6 DMA_REMAP_TIM1_DMA_CH6 +#define HAL_REMAPDMA_TIM2_DMA_CH7 DMA_REMAP_TIM2_DMA_CH7 +#define HAL_REMAPDMA_TIM3_DMA_CH6 DMA_REMAP_TIM3_DMA_CH6 + +#define IS_HAL_REMAPDMA IS_DMA_REMAP +#define __HAL_REMAPDMA_CHANNEL_ENABLE __HAL_DMA_REMAP_CHANNEL_ENABLE +#define __HAL_REMAPDMA_CHANNEL_DISABLE __HAL_DMA_REMAP_CHANNEL_DISABLE + +#if defined(STM32L4) + +#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI1 HAL_DMAMUX1_REQ_GEN_EXTI1 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI2 HAL_DMAMUX1_REQ_GEN_EXTI2 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI3 HAL_DMAMUX1_REQ_GEN_EXTI3 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI4 HAL_DMAMUX1_REQ_GEN_EXTI4 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI5 HAL_DMAMUX1_REQ_GEN_EXTI5 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI6 HAL_DMAMUX1_REQ_GEN_EXTI6 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI7 HAL_DMAMUX1_REQ_GEN_EXTI7 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI8 HAL_DMAMUX1_REQ_GEN_EXTI8 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI9 HAL_DMAMUX1_REQ_GEN_EXTI9 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI10 HAL_DMAMUX1_REQ_GEN_EXTI10 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI11 HAL_DMAMUX1_REQ_GEN_EXTI11 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI12 HAL_DMAMUX1_REQ_GEN_EXTI12 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI13 HAL_DMAMUX1_REQ_GEN_EXTI13 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI14 HAL_DMAMUX1_REQ_GEN_EXTI14 +#define HAL_DMAMUX1_REQUEST_GEN_EXTI15 HAL_DMAMUX1_REQ_GEN_EXTI15 +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH3_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH3_EVT +#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT +#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT +#define HAL_DMAMUX1_REQUEST_GEN_DSI_TE HAL_DMAMUX1_REQ_GEN_DSI_TE +#define HAL_DMAMUX1_REQUEST_GEN_DSI_EOT HAL_DMAMUX1_REQ_GEN_DSI_EOT +#define HAL_DMAMUX1_REQUEST_GEN_DMA2D_EOT HAL_DMAMUX1_REQ_GEN_DMA2D_EOT +#define HAL_DMAMUX1_REQUEST_GEN_LTDC_IT HAL_DMAMUX1_REQ_GEN_LTDC_IT + +#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT +#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING +#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING +#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING + +#if defined(STM32L4R5xx) || defined(STM32L4R9xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx) +#define DMA_REQUEST_DCMI_PSSI DMA_REQUEST_DCMI +#endif + +#endif /* STM32L4 */ + +#if defined(STM32G0) +#define DMA_REQUEST_DAC1_CHANNEL1 DMA_REQUEST_DAC1_CH1 +#define DMA_REQUEST_DAC1_CHANNEL2 DMA_REQUEST_DAC1_CH2 +#define DMA_REQUEST_TIM16_TRIG_COM DMA_REQUEST_TIM16_COM +#define DMA_REQUEST_TIM17_TRIG_COM DMA_REQUEST_TIM17_COM + +#define LL_DMAMUX_REQ_TIM16_TRIG_COM LL_DMAMUX_REQ_TIM16_COM +#define LL_DMAMUX_REQ_TIM17_TRIG_COM LL_DMAMUX_REQ_TIM17_COM +#endif + +#if defined(STM32H7) + +#define DMA_REQUEST_DAC1 DMA_REQUEST_DAC1_CH1 +#define DMA_REQUEST_DAC2 DMA_REQUEST_DAC1_CH2 + +#define BDMA_REQUEST_LP_UART1_RX BDMA_REQUEST_LPUART1_RX +#define BDMA_REQUEST_LP_UART1_TX BDMA_REQUEST_LPUART1_TX + +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT +#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT +#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT +#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT +#define HAL_DMAMUX1_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX1_REQ_GEN_LPTIM3_OUT +#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 +#define HAL_DMAMUX1_REQUEST_GEN_TIM12_TRGO HAL_DMAMUX1_REQ_GEN_TIM12_TRGO + +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH0_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH0_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH1_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH1_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH2_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH2_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH3_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH3_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH4_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH4_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH5_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH5_EVT +#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH6_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH6_EVT +#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_RX_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_TX_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM2_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX2_REQ_GEN_LPTIM2_OUT +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM3_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX2_REQ_GEN_LPTIM3_OUT +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM4_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM4_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_LPTIM5_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM5_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_I2C4_WKUP HAL_DMAMUX2_REQ_GEN_I2C4_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_SPI6_WKUP HAL_DMAMUX2_REQ_GEN_SPI6_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_COMP1_OUT HAL_DMAMUX2_REQ_GEN_COMP1_OUT +#define HAL_DMAMUX2_REQUEST_GEN_COMP2_OUT HAL_DMAMUX2_REQ_GEN_COMP2_OUT +#define HAL_DMAMUX2_REQUEST_GEN_RTC_WKUP HAL_DMAMUX2_REQ_GEN_RTC_WKUP +#define HAL_DMAMUX2_REQUEST_GEN_EXTI0 HAL_DMAMUX2_REQ_GEN_EXTI0 +#define HAL_DMAMUX2_REQUEST_GEN_EXTI2 HAL_DMAMUX2_REQ_GEN_EXTI2 +#define HAL_DMAMUX2_REQUEST_GEN_I2C4_IT_EVT HAL_DMAMUX2_REQ_GEN_I2C4_IT_EVT +#define HAL_DMAMUX2_REQUEST_GEN_SPI6_IT HAL_DMAMUX2_REQ_GEN_SPI6_IT +#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_TX_IT +#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_RX_IT +#define HAL_DMAMUX2_REQUEST_GEN_ADC3_IT HAL_DMAMUX2_REQ_GEN_ADC3_IT +#define HAL_DMAMUX2_REQUEST_GEN_ADC3_AWD1_OUT HAL_DMAMUX2_REQ_GEN_ADC3_AWD1_OUT +#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH0_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH0_IT +#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH1_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH1_IT + +#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT +#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING +#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING +#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING + +#define DFSDM_FILTER_EXT_TRIG_LPTIM1 DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT +#define DFSDM_FILTER_EXT_TRIG_LPTIM2 DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT +#define DFSDM_FILTER_EXT_TRIG_LPTIM3 DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT + +#define DAC_TRIGGER_LP1_OUT DAC_TRIGGER_LPTIM1_OUT +#define DAC_TRIGGER_LP2_OUT DAC_TRIGGER_LPTIM2_OUT + +#endif /* STM32H7 */ + +#if defined(STM32U5) +#define GPDMA1_REQUEST_DCMI GPDMA1_REQUEST_DCMI_PSSI +#endif /* STM32U5 */ +/** + * @} + */ + +/** @defgroup HAL_FLASH_Aliased_Defines HAL FLASH Aliased Defines maintained for legacy purpose + * @{ + */ + +#define TYPEPROGRAM_BYTE FLASH_TYPEPROGRAM_BYTE +#define TYPEPROGRAM_HALFWORD FLASH_TYPEPROGRAM_HALFWORD +#define TYPEPROGRAM_WORD FLASH_TYPEPROGRAM_WORD +#define TYPEPROGRAM_DOUBLEWORD FLASH_TYPEPROGRAM_DOUBLEWORD +#define TYPEERASE_SECTORS FLASH_TYPEERASE_SECTORS +#define TYPEERASE_PAGES FLASH_TYPEERASE_PAGES +#define TYPEERASE_PAGEERASE FLASH_TYPEERASE_PAGES +#define TYPEERASE_MASSERASE FLASH_TYPEERASE_MASSERASE +#define WRPSTATE_DISABLE OB_WRPSTATE_DISABLE +#define WRPSTATE_ENABLE OB_WRPSTATE_ENABLE +#define HAL_FLASH_TIMEOUT_VALUE FLASH_TIMEOUT_VALUE +#define OBEX_PCROP OPTIONBYTE_PCROP +#define OBEX_BOOTCONFIG OPTIONBYTE_BOOTCONFIG +#define PCROPSTATE_DISABLE OB_PCROP_STATE_DISABLE +#define PCROPSTATE_ENABLE OB_PCROP_STATE_ENABLE +#define TYPEERASEDATA_BYTE FLASH_TYPEERASEDATA_BYTE +#define TYPEERASEDATA_HALFWORD FLASH_TYPEERASEDATA_HALFWORD +#define TYPEERASEDATA_WORD FLASH_TYPEERASEDATA_WORD +#define TYPEPROGRAMDATA_BYTE FLASH_TYPEPROGRAMDATA_BYTE +#define TYPEPROGRAMDATA_HALFWORD FLASH_TYPEPROGRAMDATA_HALFWORD +#define TYPEPROGRAMDATA_WORD FLASH_TYPEPROGRAMDATA_WORD +#define TYPEPROGRAMDATA_FASTBYTE FLASH_TYPEPROGRAMDATA_FASTBYTE +#define TYPEPROGRAMDATA_FASTHALFWORD FLASH_TYPEPROGRAMDATA_FASTHALFWORD +#define TYPEPROGRAMDATA_FASTWORD FLASH_TYPEPROGRAMDATA_FASTWORD +#define PAGESIZE FLASH_PAGE_SIZE +#define TYPEPROGRAM_FASTBYTE FLASH_TYPEPROGRAM_BYTE +#define TYPEPROGRAM_FASTHALFWORD FLASH_TYPEPROGRAM_HALFWORD +#define TYPEPROGRAM_FASTWORD FLASH_TYPEPROGRAM_WORD +#define VOLTAGE_RANGE_1 FLASH_VOLTAGE_RANGE_1 +#define VOLTAGE_RANGE_2 FLASH_VOLTAGE_RANGE_2 +#define VOLTAGE_RANGE_3 FLASH_VOLTAGE_RANGE_3 +#define VOLTAGE_RANGE_4 FLASH_VOLTAGE_RANGE_4 +#define TYPEPROGRAM_FAST FLASH_TYPEPROGRAM_FAST +#define TYPEPROGRAM_FAST_AND_LAST FLASH_TYPEPROGRAM_FAST_AND_LAST +#define WRPAREA_BANK1_AREAA OB_WRPAREA_BANK1_AREAA +#define WRPAREA_BANK1_AREAB OB_WRPAREA_BANK1_AREAB +#define WRPAREA_BANK2_AREAA OB_WRPAREA_BANK2_AREAA +#define WRPAREA_BANK2_AREAB OB_WRPAREA_BANK2_AREAB +#define IWDG_STDBY_FREEZE OB_IWDG_STDBY_FREEZE +#define IWDG_STDBY_ACTIVE OB_IWDG_STDBY_RUN +#define IWDG_STOP_FREEZE OB_IWDG_STOP_FREEZE +#define IWDG_STOP_ACTIVE OB_IWDG_STOP_RUN +#define FLASH_ERROR_NONE HAL_FLASH_ERROR_NONE +#define FLASH_ERROR_RD HAL_FLASH_ERROR_RD +#define FLASH_ERROR_PG HAL_FLASH_ERROR_PROG +#define FLASH_ERROR_PGP HAL_FLASH_ERROR_PGS +#define FLASH_ERROR_WRP HAL_FLASH_ERROR_WRP +#define FLASH_ERROR_OPTV HAL_FLASH_ERROR_OPTV +#define FLASH_ERROR_OPTVUSR HAL_FLASH_ERROR_OPTVUSR +#define FLASH_ERROR_PROG HAL_FLASH_ERROR_PROG +#define FLASH_ERROR_OP HAL_FLASH_ERROR_OPERATION +#define FLASH_ERROR_PGA HAL_FLASH_ERROR_PGA +#define FLASH_ERROR_SIZE HAL_FLASH_ERROR_SIZE +#define FLASH_ERROR_SIZ HAL_FLASH_ERROR_SIZE +#define FLASH_ERROR_PGS HAL_FLASH_ERROR_PGS +#define FLASH_ERROR_MIS HAL_FLASH_ERROR_MIS +#define FLASH_ERROR_FAST HAL_FLASH_ERROR_FAST +#define FLASH_ERROR_FWWERR HAL_FLASH_ERROR_FWWERR +#define FLASH_ERROR_NOTZERO HAL_FLASH_ERROR_NOTZERO +#define FLASH_ERROR_OPERATION HAL_FLASH_ERROR_OPERATION +#define FLASH_ERROR_ERS HAL_FLASH_ERROR_ERS +#define OB_WDG_SW OB_IWDG_SW +#define OB_WDG_HW OB_IWDG_HW +#define OB_SDADC12_VDD_MONITOR_SET OB_SDACD_VDD_MONITOR_SET +#define OB_SDADC12_VDD_MONITOR_RESET OB_SDACD_VDD_MONITOR_RESET +#define OB_RAM_PARITY_CHECK_SET OB_SRAM_PARITY_SET +#define OB_RAM_PARITY_CHECK_RESET OB_SRAM_PARITY_RESET +#define IS_OB_SDADC12_VDD_MONITOR IS_OB_SDACD_VDD_MONITOR +#define OB_RDP_LEVEL0 OB_RDP_LEVEL_0 +#define OB_RDP_LEVEL1 OB_RDP_LEVEL_1 +#define OB_RDP_LEVEL2 OB_RDP_LEVEL_2 +#if defined(STM32G0) || defined(STM32C0) +#define OB_BOOT_LOCK_DISABLE OB_BOOT_ENTRY_FORCED_NONE +#define OB_BOOT_LOCK_ENABLE OB_BOOT_ENTRY_FORCED_FLASH +#else +#define OB_BOOT_ENTRY_FORCED_NONE OB_BOOT_LOCK_DISABLE +#define OB_BOOT_ENTRY_FORCED_FLASH OB_BOOT_LOCK_ENABLE +#endif +#if defined(STM32H7) +#define FLASH_FLAG_SNECCE_BANK1RR FLASH_FLAG_SNECCERR_BANK1 +#define FLASH_FLAG_DBECCE_BANK1RR FLASH_FLAG_DBECCERR_BANK1 +#define FLASH_FLAG_STRBER_BANK1R FLASH_FLAG_STRBERR_BANK1 +#define FLASH_FLAG_SNECCE_BANK2RR FLASH_FLAG_SNECCERR_BANK2 +#define FLASH_FLAG_DBECCE_BANK2RR FLASH_FLAG_DBECCERR_BANK2 +#define FLASH_FLAG_STRBER_BANK2R FLASH_FLAG_STRBERR_BANK2 +#define FLASH_FLAG_WDW FLASH_FLAG_WBNE +#define OB_WRP_SECTOR_All OB_WRP_SECTOR_ALL +#endif /* STM32H7 */ +#if defined(STM32U5) +#define OB_USER_nRST_STOP OB_USER_NRST_STOP +#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY +#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW +#define OB_USER_nSWBOOT0 OB_USER_NSWBOOT0 +#define OB_USER_nBOOT0 OB_USER_NBOOT0 +#define OB_nBOOT0_RESET OB_NBOOT0_RESET +#define OB_nBOOT0_SET OB_NBOOT0_SET +#endif /* STM32U5 */ + +/** + * @} + */ + +/** @defgroup HAL_JPEG_Aliased_Macros HAL JPEG Aliased Macros maintained for legacy purpose + * @{ + */ + +#if defined(STM32H7) +#define __HAL_RCC_JPEG_CLK_ENABLE __HAL_RCC_JPGDECEN_CLK_ENABLE +#define __HAL_RCC_JPEG_CLK_DISABLE __HAL_RCC_JPGDECEN_CLK_DISABLE +#define __HAL_RCC_JPEG_FORCE_RESET __HAL_RCC_JPGDECRST_FORCE_RESET +#define __HAL_RCC_JPEG_RELEASE_RESET __HAL_RCC_JPGDECRST_RELEASE_RESET +#define __HAL_RCC_JPEG_CLK_SLEEP_ENABLE __HAL_RCC_JPGDEC_CLK_SLEEP_ENABLE +#define __HAL_RCC_JPEG_CLK_SLEEP_DISABLE __HAL_RCC_JPGDEC_CLK_SLEEP_DISABLE +#endif /* STM32H7 */ + +/** + * @} + */ + +/** @defgroup HAL_SYSCFG_Aliased_Defines HAL SYSCFG Aliased Defines maintained for legacy purpose + * @{ + */ + +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA9 I2C_FASTMODEPLUS_PA9 +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA10 I2C_FASTMODEPLUS_PA10 +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB6 I2C_FASTMODEPLUS_PB6 +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB7 I2C_FASTMODEPLUS_PB7 +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB8 I2C_FASTMODEPLUS_PB8 +#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB9 I2C_FASTMODEPLUS_PB9 +#define HAL_SYSCFG_FASTMODEPLUS_I2C1 I2C_FASTMODEPLUS_I2C1 +#define HAL_SYSCFG_FASTMODEPLUS_I2C2 I2C_FASTMODEPLUS_I2C2 +#define HAL_SYSCFG_FASTMODEPLUS_I2C3 I2C_FASTMODEPLUS_I2C3 +#if defined(STM32G4) + +#define HAL_SYSCFG_EnableIOAnalogSwitchBooster HAL_SYSCFG_EnableIOSwitchBooster +#define HAL_SYSCFG_DisableIOAnalogSwitchBooster HAL_SYSCFG_DisableIOSwitchBooster +#define HAL_SYSCFG_EnableIOAnalogSwitchVDD HAL_SYSCFG_EnableIOSwitchVDD +#define HAL_SYSCFG_DisableIOAnalogSwitchVDD HAL_SYSCFG_DisableIOSwitchVDD +#endif /* STM32G4 */ + +/** + * @} + */ + + +/** @defgroup LL_FMC_Aliased_Defines LL FMC Aliased Defines maintained for compatibility purpose + * @{ + */ +#if defined(STM32L4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE FMC_NAND_WAIT_FEATURE_DISABLE +#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE FMC_NAND_WAIT_FEATURE_ENABLE +#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 FMC_NAND_MEM_BUS_WIDTH_8 +#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 FMC_NAND_MEM_BUS_WIDTH_16 +#elif defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) +#define FMC_NAND_WAIT_FEATURE_DISABLE FMC_NAND_PCC_WAIT_FEATURE_DISABLE +#define FMC_NAND_WAIT_FEATURE_ENABLE FMC_NAND_PCC_WAIT_FEATURE_ENABLE +#define FMC_NAND_MEM_BUS_WIDTH_8 FMC_NAND_PCC_MEM_BUS_WIDTH_8 +#define FMC_NAND_MEM_BUS_WIDTH_16 FMC_NAND_PCC_MEM_BUS_WIDTH_16 +#endif +/** + * @} + */ + +/** @defgroup LL_FSMC_Aliased_Defines LL FSMC Aliased Defines maintained for legacy purpose + * @{ + */ + +#define FSMC_NORSRAM_TYPEDEF FSMC_NORSRAM_TypeDef +#define FSMC_NORSRAM_EXTENDED_TYPEDEF FSMC_NORSRAM_EXTENDED_TypeDef +/** + * @} + */ + +/** @defgroup HAL_GPIO_Aliased_Macros HAL GPIO Aliased Macros maintained for legacy purpose + * @{ + */ +#define GET_GPIO_SOURCE GPIO_GET_INDEX +#define GET_GPIO_INDEX GPIO_GET_INDEX + +#if defined(STM32F4) +#define GPIO_AF12_SDMMC GPIO_AF12_SDIO +#define GPIO_AF12_SDMMC1 GPIO_AF12_SDIO +#endif + +#if defined(STM32F7) +#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 +#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 +#endif + +#if defined(STM32L4) +#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 +#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 +#endif + +#if defined(STM32H7) +#define GPIO_AF7_SDIO1 GPIO_AF7_SDMMC1 +#define GPIO_AF8_SDIO1 GPIO_AF8_SDMMC1 +#define GPIO_AF12_SDIO1 GPIO_AF12_SDMMC1 +#define GPIO_AF9_SDIO2 GPIO_AF9_SDMMC2 +#define GPIO_AF10_SDIO2 GPIO_AF10_SDMMC2 +#define GPIO_AF11_SDIO2 GPIO_AF11_SDMMC2 + +#if defined (STM32H743xx) || defined (STM32H753xx) || defined (STM32H750xx) || defined (STM32H742xx) || \ + defined (STM32H745xx) || defined (STM32H755xx) || defined (STM32H747xx) || defined (STM32H757xx) +#define GPIO_AF10_OTG2_HS GPIO_AF10_OTG2_FS +#define GPIO_AF10_OTG1_FS GPIO_AF10_OTG1_HS +#define GPIO_AF12_OTG2_FS GPIO_AF12_OTG1_FS +#endif /*STM32H743xx || STM32H753xx || STM32H750xx || STM32H742xx || STM32H745xx || STM32H755xx || STM32H747xx || STM32H757xx */ +#endif /* STM32H7 */ + +#define GPIO_AF0_LPTIM GPIO_AF0_LPTIM1 +#define GPIO_AF1_LPTIM GPIO_AF1_LPTIM1 +#define GPIO_AF2_LPTIM GPIO_AF2_LPTIM1 + +#if defined(STM32L0) || defined(STM32L4) || defined(STM32F4) || defined(STM32F2) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32WB) || defined(STM32U5) +#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW +#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM +#define GPIO_SPEED_FAST GPIO_SPEED_FREQ_HIGH +#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH +#endif /* STM32L0 || STM32L4 || STM32F4 || STM32F2 || STM32F7 || STM32G4 || STM32H7 || STM32WB || STM32U5*/ + +#if defined(STM32L1) +#define GPIO_SPEED_VERY_LOW GPIO_SPEED_FREQ_LOW +#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_MEDIUM +#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_HIGH +#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH +#endif /* STM32L1 */ + +#if defined(STM32F0) || defined(STM32F3) || defined(STM32F1) +#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW +#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM +#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_HIGH +#endif /* STM32F0 || STM32F3 || STM32F1 */ + +#define GPIO_AF6_DFSDM GPIO_AF6_DFSDM1 + +#if defined(STM32U5) +#define GPIO_AF0_RTC_50Hz GPIO_AF0_RTC_50HZ +#endif /* STM32U5 */ +#if defined(STM32U5) +#define GPIO_AF0_S2DSTOP GPIO_AF0_SRDSTOP +#define GPIO_AF11_LPGPIO GPIO_AF11_LPGPIO1 +#endif /* STM32U5 */ +/** + * @} + */ + +/** @defgroup HAL_GTZC_Aliased_Defines HAL GTZC Aliased Defines maintained for legacy purpose + * @{ + */ +#if defined(STM32U5) +#define GTZC_PERIPH_DCMI GTZC_PERIPH_DCMI_PSSI +#endif /* STM32U5 */ +/** + * @} + */ + +/** @defgroup HAL_HRTIM_Aliased_Macros HAL HRTIM Aliased Macros maintained for legacy purpose + * @{ + */ +#define HRTIM_TIMDELAYEDPROTECTION_DISABLED HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DISABLED +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_EEV6 +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_EEV6 +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV6 +#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV6 +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_DEEV7 +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_DEEV7 +#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV7 +#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV7 + +#define __HAL_HRTIM_SetCounter __HAL_HRTIM_SETCOUNTER +#define __HAL_HRTIM_GetCounter __HAL_HRTIM_GETCOUNTER +#define __HAL_HRTIM_SetPeriod __HAL_HRTIM_SETPERIOD +#define __HAL_HRTIM_GetPeriod __HAL_HRTIM_GETPERIOD +#define __HAL_HRTIM_SetClockPrescaler __HAL_HRTIM_SETCLOCKPRESCALER +#define __HAL_HRTIM_GetClockPrescaler __HAL_HRTIM_GETCLOCKPRESCALER +#define __HAL_HRTIM_SetCompare __HAL_HRTIM_SETCOMPARE +#define __HAL_HRTIM_GetCompare __HAL_HRTIM_GETCOMPARE + +#if defined(STM32G4) +#define HAL_HRTIM_ExternalEventCounterConfig HAL_HRTIM_ExtEventCounterConfig +#define HAL_HRTIM_ExternalEventCounterEnable HAL_HRTIM_ExtEventCounterEnable +#define HAL_HRTIM_ExternalEventCounterDisable HAL_HRTIM_ExtEventCounterDisable +#define HAL_HRTIM_ExternalEventCounterReset HAL_HRTIM_ExtEventCounterReset +#define HRTIM_TIMEEVENT_A HRTIM_EVENTCOUNTER_A +#define HRTIM_TIMEEVENT_B HRTIM_EVENTCOUNTER_B +#define HRTIM_TIMEEVENTRESETMODE_UNCONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_UNCONDITIONAL +#define HRTIM_TIMEEVENTRESETMODE_CONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_CONDITIONAL +#endif /* STM32G4 */ + +#if defined(STM32H7) +#define HRTIM_OUTPUTSET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTSET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTSET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTSET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTSET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTSET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTSET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTSET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTSET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTSET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTSET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTSET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTSET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTSET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 + +#define HRTIM_OUTPUTRESET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTRESET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTRESET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTRESET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTRESET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 +#define HRTIM_OUTPUTRESET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 +#define HRTIM_OUTPUTRESET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 +#define HRTIM_OUTPUTRESET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 +#define HRTIM_OUTPUTRESET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 +#define HRTIM_OUTPUTRESET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 +#define HRTIM_OUTPUTRESET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 +#define HRTIM_OUTPUTRESET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 +#define HRTIM_OUTPUTRESET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 +#define HRTIM_OUTPUTRESET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 +#endif /* STM32H7 */ + +#if defined(STM32F3) +/** @brief Constants defining available sources associated to external events. + */ +#define HRTIM_EVENTSRC_1 (0x00000000U) +#define HRTIM_EVENTSRC_2 (HRTIM_EECR1_EE1SRC_0) +#define HRTIM_EVENTSRC_3 (HRTIM_EECR1_EE1SRC_1) +#define HRTIM_EVENTSRC_4 (HRTIM_EECR1_EE1SRC_1 | HRTIM_EECR1_EE1SRC_0) + +/** @brief Constants defining the DLL calibration periods (in micro seconds) + */ +#define HRTIM_CALIBRATIONRATE_7300 0x00000000U +#define HRTIM_CALIBRATIONRATE_910 (HRTIM_DLLCR_CALRTE_0) +#define HRTIM_CALIBRATIONRATE_114 (HRTIM_DLLCR_CALRTE_1) +#define HRTIM_CALIBRATIONRATE_14 (HRTIM_DLLCR_CALRTE_1 | HRTIM_DLLCR_CALRTE_0) + +#endif /* STM32F3 */ +/** + * @} + */ + +/** @defgroup HAL_I2C_Aliased_Defines HAL I2C Aliased Defines maintained for legacy purpose + * @{ + */ +#define I2C_DUALADDRESS_DISABLED I2C_DUALADDRESS_DISABLE +#define I2C_DUALADDRESS_ENABLED I2C_DUALADDRESS_ENABLE +#define I2C_GENERALCALL_DISABLED I2C_GENERALCALL_DISABLE +#define I2C_GENERALCALL_ENABLED I2C_GENERALCALL_ENABLE +#define I2C_NOSTRETCH_DISABLED I2C_NOSTRETCH_DISABLE +#define I2C_NOSTRETCH_ENABLED I2C_NOSTRETCH_ENABLE +#define I2C_ANALOGFILTER_ENABLED I2C_ANALOGFILTER_ENABLE +#define I2C_ANALOGFILTER_DISABLED I2C_ANALOGFILTER_DISABLE +#if defined(STM32F0) || defined(STM32F1) || defined(STM32F3) || defined(STM32G0) || defined(STM32L4) || defined(STM32L1) || defined(STM32F7) +#define HAL_I2C_STATE_MEM_BUSY_TX HAL_I2C_STATE_BUSY_TX +#define HAL_I2C_STATE_MEM_BUSY_RX HAL_I2C_STATE_BUSY_RX +#define HAL_I2C_STATE_MASTER_BUSY_TX HAL_I2C_STATE_BUSY_TX +#define HAL_I2C_STATE_MASTER_BUSY_RX HAL_I2C_STATE_BUSY_RX +#define HAL_I2C_STATE_SLAVE_BUSY_TX HAL_I2C_STATE_BUSY_TX +#define HAL_I2C_STATE_SLAVE_BUSY_RX HAL_I2C_STATE_BUSY_RX +#endif +/** + * @} + */ + +/** @defgroup HAL_IRDA_Aliased_Defines HAL IRDA Aliased Defines maintained for legacy purpose + * @{ + */ +#define IRDA_ONE_BIT_SAMPLE_DISABLED IRDA_ONE_BIT_SAMPLE_DISABLE +#define IRDA_ONE_BIT_SAMPLE_ENABLED IRDA_ONE_BIT_SAMPLE_ENABLE + +/** + * @} + */ + +/** @defgroup HAL_IWDG_Aliased_Defines HAL IWDG Aliased Defines maintained for legacy purpose + * @{ + */ +#define KR_KEY_RELOAD IWDG_KEY_RELOAD +#define KR_KEY_ENABLE IWDG_KEY_ENABLE +#define KR_KEY_EWA IWDG_KEY_WRITE_ACCESS_ENABLE +#define KR_KEY_DWA IWDG_KEY_WRITE_ACCESS_DISABLE +/** + * @} + */ + +/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose + * @{ + */ + +#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION +#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CLOCKSAMPLETIME_2TRANSITIONS +#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CLOCKSAMPLETIME_4TRANSITIONS +#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CLOCKSAMPLETIME_8TRANSITIONS + +#define LPTIM_CLOCKPOLARITY_RISINGEDGE LPTIM_CLOCKPOLARITY_RISING +#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CLOCKPOLARITY_FALLING +#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CLOCKPOLARITY_RISING_FALLING + +#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION +#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_TRIGSAMPLETIME_2TRANSITIONS +#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_TRIGSAMPLETIME_4TRANSITIONS +#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_TRIGSAMPLETIME_8TRANSITIONS + +/* The following 3 definition have also been present in a temporary version of lptim.h */ +/* They need to be renamed also to the right name, just in case */ +#define LPTIM_TRIGSAMPLETIME_2TRANSITION LPTIM_TRIGSAMPLETIME_2TRANSITIONS +#define LPTIM_TRIGSAMPLETIME_4TRANSITION LPTIM_TRIGSAMPLETIME_4TRANSITIONS +#define LPTIM_TRIGSAMPLETIME_8TRANSITION LPTIM_TRIGSAMPLETIME_8TRANSITIONS + + +/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose + * @{ + */ +#define HAL_LPTIM_ReadCompare HAL_LPTIM_ReadCapturedValue +/** + * @} + */ + +#if defined(STM32U5) +#define LPTIM_ISR_CC1 LPTIM_ISR_CC1IF +#define LPTIM_ISR_CC2 LPTIM_ISR_CC2IF +#define LPTIM_CHANNEL_ALL 0x00000000U +#endif /* STM32U5 */ +/** + * @} + */ + +/** @defgroup HAL_NAND_Aliased_Defines HAL NAND Aliased Defines maintained for legacy purpose + * @{ + */ +#define HAL_NAND_Read_Page HAL_NAND_Read_Page_8b +#define HAL_NAND_Write_Page HAL_NAND_Write_Page_8b +#define HAL_NAND_Read_SpareArea HAL_NAND_Read_SpareArea_8b +#define HAL_NAND_Write_SpareArea HAL_NAND_Write_SpareArea_8b + +#define NAND_AddressTypedef NAND_AddressTypeDef + +#define __ARRAY_ADDRESS ARRAY_ADDRESS +#define __ADDR_1st_CYCLE ADDR_1ST_CYCLE +#define __ADDR_2nd_CYCLE ADDR_2ND_CYCLE +#define __ADDR_3rd_CYCLE ADDR_3RD_CYCLE +#define __ADDR_4th_CYCLE ADDR_4TH_CYCLE +/** + * @} + */ + +/** @defgroup HAL_NOR_Aliased_Defines HAL NOR Aliased Defines maintained for legacy purpose + * @{ + */ +#define NOR_StatusTypedef HAL_NOR_StatusTypeDef +#define NOR_SUCCESS HAL_NOR_STATUS_SUCCESS +#define NOR_ONGOING HAL_NOR_STATUS_ONGOING +#define NOR_ERROR HAL_NOR_STATUS_ERROR +#define NOR_TIMEOUT HAL_NOR_STATUS_TIMEOUT + +#define __NOR_WRITE NOR_WRITE +#define __NOR_ADDR_SHIFT NOR_ADDR_SHIFT +/** + * @} + */ + +/** @defgroup HAL_OPAMP_Aliased_Defines HAL OPAMP Aliased Defines maintained for legacy purpose + * @{ + */ + +#define OPAMP_NONINVERTINGINPUT_VP0 OPAMP_NONINVERTINGINPUT_IO0 +#define OPAMP_NONINVERTINGINPUT_VP1 OPAMP_NONINVERTINGINPUT_IO1 +#define OPAMP_NONINVERTINGINPUT_VP2 OPAMP_NONINVERTINGINPUT_IO2 +#define OPAMP_NONINVERTINGINPUT_VP3 OPAMP_NONINVERTINGINPUT_IO3 + +#define OPAMP_SEC_NONINVERTINGINPUT_VP0 OPAMP_SEC_NONINVERTINGINPUT_IO0 +#define OPAMP_SEC_NONINVERTINGINPUT_VP1 OPAMP_SEC_NONINVERTINGINPUT_IO1 +#define OPAMP_SEC_NONINVERTINGINPUT_VP2 OPAMP_SEC_NONINVERTINGINPUT_IO2 +#define OPAMP_SEC_NONINVERTINGINPUT_VP3 OPAMP_SEC_NONINVERTINGINPUT_IO3 + +#define OPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 +#define OPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 + +#define IOPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 +#define IOPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 + +#define OPAMP_SEC_INVERTINGINPUT_VM0 OPAMP_SEC_INVERTINGINPUT_IO0 +#define OPAMP_SEC_INVERTINGINPUT_VM1 OPAMP_SEC_INVERTINGINPUT_IO1 + +#define OPAMP_INVERTINGINPUT_VINM OPAMP_SEC_INVERTINGINPUT_IO1 + +#define OPAMP_PGACONNECT_NO OPAMP_PGA_CONNECT_INVERTINGINPUT_NO +#define OPAMP_PGACONNECT_VM0 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0 +#define OPAMP_PGACONNECT_VM1 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO1 + +#if defined(STM32L1) || defined(STM32L4) || defined(STM32L5) || defined(STM32H7) || defined(STM32G4) +#define HAL_OPAMP_MSP_INIT_CB_ID HAL_OPAMP_MSPINIT_CB_ID +#define HAL_OPAMP_MSP_DEINIT_CB_ID HAL_OPAMP_MSPDEINIT_CB_ID +#endif + +#if defined(STM32L4) || defined(STM32L5) +#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALPOWER +#elif defined(STM32G4) +#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALSPEED +#endif + +/** + * @} + */ + +/** @defgroup HAL_I2S_Aliased_Defines HAL I2S Aliased Defines maintained for legacy purpose + * @{ + */ +#define I2S_STANDARD_PHILLIPS I2S_STANDARD_PHILIPS + +#if defined(STM32H7) +#define I2S_IT_TXE I2S_IT_TXP +#define I2S_IT_RXNE I2S_IT_RXP + +#define I2S_FLAG_TXE I2S_FLAG_TXP +#define I2S_FLAG_RXNE I2S_FLAG_RXP +#endif + +#if defined(STM32F7) +#define I2S_CLOCK_SYSCLK I2S_CLOCK_PLL +#endif +/** + * @} + */ + +/** @defgroup HAL_PCCARD_Aliased_Defines HAL PCCARD Aliased Defines maintained for legacy purpose + * @{ + */ + +/* Compact Flash-ATA registers description */ +#define CF_DATA ATA_DATA +#define CF_SECTOR_COUNT ATA_SECTOR_COUNT +#define CF_SECTOR_NUMBER ATA_SECTOR_NUMBER +#define CF_CYLINDER_LOW ATA_CYLINDER_LOW +#define CF_CYLINDER_HIGH ATA_CYLINDER_HIGH +#define CF_CARD_HEAD ATA_CARD_HEAD +#define CF_STATUS_CMD ATA_STATUS_CMD +#define CF_STATUS_CMD_ALTERNATE ATA_STATUS_CMD_ALTERNATE +#define CF_COMMON_DATA_AREA ATA_COMMON_DATA_AREA + +/* Compact Flash-ATA commands */ +#define CF_READ_SECTOR_CMD ATA_READ_SECTOR_CMD +#define CF_WRITE_SECTOR_CMD ATA_WRITE_SECTOR_CMD +#define CF_ERASE_SECTOR_CMD ATA_ERASE_SECTOR_CMD +#define CF_IDENTIFY_CMD ATA_IDENTIFY_CMD + +#define PCCARD_StatusTypedef HAL_PCCARD_StatusTypeDef +#define PCCARD_SUCCESS HAL_PCCARD_STATUS_SUCCESS +#define PCCARD_ONGOING HAL_PCCARD_STATUS_ONGOING +#define PCCARD_ERROR HAL_PCCARD_STATUS_ERROR +#define PCCARD_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT +/** + * @} + */ + +/** @defgroup HAL_RTC_Aliased_Defines HAL RTC Aliased Defines maintained for legacy purpose + * @{ + */ + +#define FORMAT_BIN RTC_FORMAT_BIN +#define FORMAT_BCD RTC_FORMAT_BCD + +#define RTC_ALARMSUBSECONDMASK_None RTC_ALARMSUBSECONDMASK_NONE +#define RTC_TAMPERERASEBACKUP_DISABLED RTC_TAMPER_ERASE_BACKUP_DISABLE +#define RTC_TAMPERMASK_FLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE +#define RTC_TAMPERMASK_FLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE + +#define RTC_MASKTAMPERFLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE +#define RTC_MASKTAMPERFLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE +#define RTC_TAMPERERASEBACKUP_ENABLED RTC_TAMPER_ERASE_BACKUP_ENABLE +#define RTC_TAMPER1_2_INTERRUPT RTC_ALL_TAMPER_INTERRUPT +#define RTC_TAMPER1_2_3_INTERRUPT RTC_ALL_TAMPER_INTERRUPT + +#define RTC_TIMESTAMPPIN_PC13 RTC_TIMESTAMPPIN_DEFAULT +#define RTC_TIMESTAMPPIN_PA0 RTC_TIMESTAMPPIN_POS1 +#define RTC_TIMESTAMPPIN_PI8 RTC_TIMESTAMPPIN_POS1 +#define RTC_TIMESTAMPPIN_PC1 RTC_TIMESTAMPPIN_POS2 + +#define RTC_OUTPUT_REMAP_PC13 RTC_OUTPUT_REMAP_NONE +#define RTC_OUTPUT_REMAP_PB14 RTC_OUTPUT_REMAP_POS1 +#define RTC_OUTPUT_REMAP_PB2 RTC_OUTPUT_REMAP_POS1 + +#define RTC_TAMPERPIN_PC13 RTC_TAMPERPIN_DEFAULT +#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1 +#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1 + +#if defined(STM32F7) +#define RTC_TAMPCR_TAMPXE RTC_TAMPER_ENABLE_BITS_MASK +#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_IT_ENABLE_BITS_MASK +#endif /* STM32F7 */ + +#if defined(STM32H7) +#define RTC_TAMPCR_TAMPXE RTC_TAMPER_X +#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_X_INTERRUPT +#endif /* STM32H7 */ + +#if defined(STM32F7) || defined(STM32H7) +#define RTC_TAMPER1_INTERRUPT RTC_IT_TAMP1 +#define RTC_TAMPER2_INTERRUPT RTC_IT_TAMP2 +#define RTC_TAMPER3_INTERRUPT RTC_IT_TAMP3 +#define RTC_ALL_TAMPER_INTERRUPT RTC_IT_TAMP +#endif /* STM32F7 || STM32H7 */ + +/** + * @} + */ + + +/** @defgroup HAL_SMARTCARD_Aliased_Defines HAL SMARTCARD Aliased Defines maintained for legacy purpose + * @{ + */ +#define SMARTCARD_NACK_ENABLED SMARTCARD_NACK_ENABLE +#define SMARTCARD_NACK_DISABLED SMARTCARD_NACK_DISABLE + +#define SMARTCARD_ONEBIT_SAMPLING_DISABLED SMARTCARD_ONE_BIT_SAMPLE_DISABLE +#define SMARTCARD_ONEBIT_SAMPLING_ENABLED SMARTCARD_ONE_BIT_SAMPLE_ENABLE +#define SMARTCARD_ONEBIT_SAMPLING_DISABLE SMARTCARD_ONE_BIT_SAMPLE_DISABLE +#define SMARTCARD_ONEBIT_SAMPLING_ENABLE SMARTCARD_ONE_BIT_SAMPLE_ENABLE + +#define SMARTCARD_TIMEOUT_DISABLED SMARTCARD_TIMEOUT_DISABLE +#define SMARTCARD_TIMEOUT_ENABLED SMARTCARD_TIMEOUT_ENABLE + +#define SMARTCARD_LASTBIT_DISABLED SMARTCARD_LASTBIT_DISABLE +#define SMARTCARD_LASTBIT_ENABLED SMARTCARD_LASTBIT_ENABLE +/** + * @} + */ + + +/** @defgroup HAL_SMBUS_Aliased_Defines HAL SMBUS Aliased Defines maintained for legacy purpose + * @{ + */ +#define SMBUS_DUALADDRESS_DISABLED SMBUS_DUALADDRESS_DISABLE +#define SMBUS_DUALADDRESS_ENABLED SMBUS_DUALADDRESS_ENABLE +#define SMBUS_GENERALCALL_DISABLED SMBUS_GENERALCALL_DISABLE +#define SMBUS_GENERALCALL_ENABLED SMBUS_GENERALCALL_ENABLE +#define SMBUS_NOSTRETCH_DISABLED SMBUS_NOSTRETCH_DISABLE +#define SMBUS_NOSTRETCH_ENABLED SMBUS_NOSTRETCH_ENABLE +#define SMBUS_ANALOGFILTER_ENABLED SMBUS_ANALOGFILTER_ENABLE +#define SMBUS_ANALOGFILTER_DISABLED SMBUS_ANALOGFILTER_DISABLE +#define SMBUS_PEC_DISABLED SMBUS_PEC_DISABLE +#define SMBUS_PEC_ENABLED SMBUS_PEC_ENABLE +#define HAL_SMBUS_STATE_SLAVE_LISTEN HAL_SMBUS_STATE_LISTEN +/** + * @} + */ + +/** @defgroup HAL_SPI_Aliased_Defines HAL SPI Aliased Defines maintained for legacy purpose + * @{ + */ +#define SPI_TIMODE_DISABLED SPI_TIMODE_DISABLE +#define SPI_TIMODE_ENABLED SPI_TIMODE_ENABLE + +#define SPI_CRCCALCULATION_DISABLED SPI_CRCCALCULATION_DISABLE +#define SPI_CRCCALCULATION_ENABLED SPI_CRCCALCULATION_ENABLE + +#define SPI_NSS_PULSE_DISABLED SPI_NSS_PULSE_DISABLE +#define SPI_NSS_PULSE_ENABLED SPI_NSS_PULSE_ENABLE + +#if defined(STM32H7) + +#define SPI_FLAG_TXE SPI_FLAG_TXP +#define SPI_FLAG_RXNE SPI_FLAG_RXP + +#define SPI_IT_TXE SPI_IT_TXP +#define SPI_IT_RXNE SPI_IT_RXP + +#define SPI_FRLVL_EMPTY SPI_RX_FIFO_0PACKET +#define SPI_FRLVL_QUARTER_FULL SPI_RX_FIFO_1PACKET +#define SPI_FRLVL_HALF_FULL SPI_RX_FIFO_2PACKET +#define SPI_FRLVL_FULL SPI_RX_FIFO_3PACKET + +#endif /* STM32H7 */ + +/** + * @} + */ + +/** @defgroup HAL_TIM_Aliased_Defines HAL TIM Aliased Defines maintained for legacy purpose + * @{ + */ +#define CCER_CCxE_MASK TIM_CCER_CCxE_MASK +#define CCER_CCxNE_MASK TIM_CCER_CCxNE_MASK + +#define TIM_DMABase_CR1 TIM_DMABASE_CR1 +#define TIM_DMABase_CR2 TIM_DMABASE_CR2 +#define TIM_DMABase_SMCR TIM_DMABASE_SMCR +#define TIM_DMABase_DIER TIM_DMABASE_DIER +#define TIM_DMABase_SR TIM_DMABASE_SR +#define TIM_DMABase_EGR TIM_DMABASE_EGR +#define TIM_DMABase_CCMR1 TIM_DMABASE_CCMR1 +#define TIM_DMABase_CCMR2 TIM_DMABASE_CCMR2 +#define TIM_DMABase_CCER TIM_DMABASE_CCER +#define TIM_DMABase_CNT TIM_DMABASE_CNT +#define TIM_DMABase_PSC TIM_DMABASE_PSC +#define TIM_DMABase_ARR TIM_DMABASE_ARR +#define TIM_DMABase_RCR TIM_DMABASE_RCR +#define TIM_DMABase_CCR1 TIM_DMABASE_CCR1 +#define TIM_DMABase_CCR2 TIM_DMABASE_CCR2 +#define TIM_DMABase_CCR3 TIM_DMABASE_CCR3 +#define TIM_DMABase_CCR4 TIM_DMABASE_CCR4 +#define TIM_DMABase_BDTR TIM_DMABASE_BDTR +#define TIM_DMABase_DCR TIM_DMABASE_DCR +#define TIM_DMABase_DMAR TIM_DMABASE_DMAR +#define TIM_DMABase_OR1 TIM_DMABASE_OR1 +#define TIM_DMABase_CCMR3 TIM_DMABASE_CCMR3 +#define TIM_DMABase_CCR5 TIM_DMABASE_CCR5 +#define TIM_DMABase_CCR6 TIM_DMABASE_CCR6 +#define TIM_DMABase_OR2 TIM_DMABASE_OR2 +#define TIM_DMABase_OR3 TIM_DMABASE_OR3 +#define TIM_DMABase_OR TIM_DMABASE_OR + +#define TIM_EventSource_Update TIM_EVENTSOURCE_UPDATE +#define TIM_EventSource_CC1 TIM_EVENTSOURCE_CC1 +#define TIM_EventSource_CC2 TIM_EVENTSOURCE_CC2 +#define TIM_EventSource_CC3 TIM_EVENTSOURCE_CC3 +#define TIM_EventSource_CC4 TIM_EVENTSOURCE_CC4 +#define TIM_EventSource_COM TIM_EVENTSOURCE_COM +#define TIM_EventSource_Trigger TIM_EVENTSOURCE_TRIGGER +#define TIM_EventSource_Break TIM_EVENTSOURCE_BREAK +#define TIM_EventSource_Break2 TIM_EVENTSOURCE_BREAK2 + +#define TIM_DMABurstLength_1Transfer TIM_DMABURSTLENGTH_1TRANSFER +#define TIM_DMABurstLength_2Transfers TIM_DMABURSTLENGTH_2TRANSFERS +#define TIM_DMABurstLength_3Transfers TIM_DMABURSTLENGTH_3TRANSFERS +#define TIM_DMABurstLength_4Transfers TIM_DMABURSTLENGTH_4TRANSFERS +#define TIM_DMABurstLength_5Transfers TIM_DMABURSTLENGTH_5TRANSFERS +#define TIM_DMABurstLength_6Transfers TIM_DMABURSTLENGTH_6TRANSFERS +#define TIM_DMABurstLength_7Transfers TIM_DMABURSTLENGTH_7TRANSFERS +#define TIM_DMABurstLength_8Transfers TIM_DMABURSTLENGTH_8TRANSFERS +#define TIM_DMABurstLength_9Transfers TIM_DMABURSTLENGTH_9TRANSFERS +#define TIM_DMABurstLength_10Transfers TIM_DMABURSTLENGTH_10TRANSFERS +#define TIM_DMABurstLength_11Transfers TIM_DMABURSTLENGTH_11TRANSFERS +#define TIM_DMABurstLength_12Transfers TIM_DMABURSTLENGTH_12TRANSFERS +#define TIM_DMABurstLength_13Transfers TIM_DMABURSTLENGTH_13TRANSFERS +#define TIM_DMABurstLength_14Transfers TIM_DMABURSTLENGTH_14TRANSFERS +#define TIM_DMABurstLength_15Transfers TIM_DMABURSTLENGTH_15TRANSFERS +#define TIM_DMABurstLength_16Transfers TIM_DMABURSTLENGTH_16TRANSFERS +#define TIM_DMABurstLength_17Transfers TIM_DMABURSTLENGTH_17TRANSFERS +#define TIM_DMABurstLength_18Transfers TIM_DMABURSTLENGTH_18TRANSFERS + +#if defined(STM32L0) +#define TIM22_TI1_GPIO1 TIM22_TI1_GPIO +#define TIM22_TI1_GPIO2 TIM22_TI1_GPIO +#endif + +#if defined(STM32F3) +#define IS_TIM_HALL_INTERFACE_INSTANCE IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE +#endif + +#if defined(STM32H7) +#define TIM_TIM1_ETR_COMP1_OUT TIM_TIM1_ETR_COMP1 +#define TIM_TIM1_ETR_COMP2_OUT TIM_TIM1_ETR_COMP2 +#define TIM_TIM8_ETR_COMP1_OUT TIM_TIM8_ETR_COMP1 +#define TIM_TIM8_ETR_COMP2_OUT TIM_TIM8_ETR_COMP2 +#define TIM_TIM2_ETR_COMP1_OUT TIM_TIM2_ETR_COMP1 +#define TIM_TIM2_ETR_COMP2_OUT TIM_TIM2_ETR_COMP2 +#define TIM_TIM3_ETR_COMP1_OUT TIM_TIM3_ETR_COMP1 +#define TIM_TIM1_TI1_COMP1_OUT TIM_TIM1_TI1_COMP1 +#define TIM_TIM8_TI1_COMP2_OUT TIM_TIM8_TI1_COMP2 +#define TIM_TIM2_TI4_COMP1_OUT TIM_TIM2_TI4_COMP1 +#define TIM_TIM2_TI4_COMP2_OUT TIM_TIM2_TI4_COMP2 +#define TIM_TIM2_TI4_COMP1COMP2_OUT TIM_TIM2_TI4_COMP1_COMP2 +#define TIM_TIM3_TI1_COMP1_OUT TIM_TIM3_TI1_COMP1 +#define TIM_TIM3_TI1_COMP2_OUT TIM_TIM3_TI1_COMP2 +#define TIM_TIM3_TI1_COMP1COMP2_OUT TIM_TIM3_TI1_COMP1_COMP2 +#endif + +#if defined(STM32U5) || defined(STM32MP2) +#define OCREF_CLEAR_SELECT_Pos OCREF_CLEAR_SELECT_POS +#define OCREF_CLEAR_SELECT_Msk OCREF_CLEAR_SELECT_MSK +#endif +/** + * @} + */ + +/** @defgroup HAL_TSC_Aliased_Defines HAL TSC Aliased Defines maintained for legacy purpose + * @{ + */ +#define TSC_SYNC_POL_FALL TSC_SYNC_POLARITY_FALLING +#define TSC_SYNC_POL_RISE_HIGH TSC_SYNC_POLARITY_RISING +/** + * @} + */ + +/** @defgroup HAL_UART_Aliased_Defines HAL UART Aliased Defines maintained for legacy purpose + * @{ + */ +#define UART_ONEBIT_SAMPLING_DISABLED UART_ONE_BIT_SAMPLE_DISABLE +#define UART_ONEBIT_SAMPLING_ENABLED UART_ONE_BIT_SAMPLE_ENABLE +#define UART_ONE_BIT_SAMPLE_DISABLED UART_ONE_BIT_SAMPLE_DISABLE +#define UART_ONE_BIT_SAMPLE_ENABLED UART_ONE_BIT_SAMPLE_ENABLE + +#define __HAL_UART_ONEBIT_ENABLE __HAL_UART_ONE_BIT_SAMPLE_ENABLE +#define __HAL_UART_ONEBIT_DISABLE __HAL_UART_ONE_BIT_SAMPLE_DISABLE + +#define __DIV_SAMPLING16 UART_DIV_SAMPLING16 +#define __DIVMANT_SAMPLING16 UART_DIVMANT_SAMPLING16 +#define __DIVFRAQ_SAMPLING16 UART_DIVFRAQ_SAMPLING16 +#define __UART_BRR_SAMPLING16 UART_BRR_SAMPLING16 + +#define __DIV_SAMPLING8 UART_DIV_SAMPLING8 +#define __DIVMANT_SAMPLING8 UART_DIVMANT_SAMPLING8 +#define __DIVFRAQ_SAMPLING8 UART_DIVFRAQ_SAMPLING8 +#define __UART_BRR_SAMPLING8 UART_BRR_SAMPLING8 + +#define __DIV_LPUART UART_DIV_LPUART + +#define UART_WAKEUPMETHODE_IDLELINE UART_WAKEUPMETHOD_IDLELINE +#define UART_WAKEUPMETHODE_ADDRESSMARK UART_WAKEUPMETHOD_ADDRESSMARK + +/** + * @} + */ + + +/** @defgroup HAL_USART_Aliased_Defines HAL USART Aliased Defines maintained for legacy purpose + * @{ + */ + +#define USART_CLOCK_DISABLED USART_CLOCK_DISABLE +#define USART_CLOCK_ENABLED USART_CLOCK_ENABLE + +#define USARTNACK_ENABLED USART_NACK_ENABLE +#define USARTNACK_DISABLED USART_NACK_DISABLE +/** + * @} + */ + +/** @defgroup HAL_WWDG_Aliased_Defines HAL WWDG Aliased Defines maintained for legacy purpose + * @{ + */ +#define CFR_BASE WWDG_CFR_BASE + +/** + * @} + */ + +/** @defgroup HAL_CAN_Aliased_Defines HAL CAN Aliased Defines maintained for legacy purpose + * @{ + */ +#define CAN_FilterFIFO0 CAN_FILTER_FIFO0 +#define CAN_FilterFIFO1 CAN_FILTER_FIFO1 +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME +#define INAK_TIMEOUT CAN_TIMEOUT_VALUE +#define SLAK_TIMEOUT CAN_TIMEOUT_VALUE +#define CAN_TXSTATUS_FAILED ((uint8_t)0x00U) +#define CAN_TXSTATUS_OK ((uint8_t)0x01U) +#define CAN_TXSTATUS_PENDING ((uint8_t)0x02U) + +/** + * @} + */ + +/** @defgroup HAL_ETH_Aliased_Defines HAL ETH Aliased Defines maintained for legacy purpose + * @{ + */ + +#define VLAN_TAG ETH_VLAN_TAG +#define MIN_ETH_PAYLOAD ETH_MIN_ETH_PAYLOAD +#define MAX_ETH_PAYLOAD ETH_MAX_ETH_PAYLOAD +#define JUMBO_FRAME_PAYLOAD ETH_JUMBO_FRAME_PAYLOAD +#define MACMIIAR_CR_MASK ETH_MACMIIAR_CR_MASK +#define MACCR_CLEAR_MASK ETH_MACCR_CLEAR_MASK +#define MACFCR_CLEAR_MASK ETH_MACFCR_CLEAR_MASK +#define DMAOMR_CLEAR_MASK ETH_DMAOMR_CLEAR_MASK + +#define ETH_MMCCR 0x00000100U +#define ETH_MMCRIR 0x00000104U +#define ETH_MMCTIR 0x00000108U +#define ETH_MMCRIMR 0x0000010CU +#define ETH_MMCTIMR 0x00000110U +#define ETH_MMCTGFSCCR 0x0000014CU +#define ETH_MMCTGFMSCCR 0x00000150U +#define ETH_MMCTGFCR 0x00000168U +#define ETH_MMCRFCECR 0x00000194U +#define ETH_MMCRFAECR 0x00000198U +#define ETH_MMCRGUFCR 0x000001C4U + +#define ETH_MAC_TXFIFO_FULL 0x02000000U /* Tx FIFO full */ +#define ETH_MAC_TXFIFONOT_EMPTY 0x01000000U /* Tx FIFO not empty */ +#define ETH_MAC_TXFIFO_WRITE_ACTIVE 0x00400000U /* Tx FIFO write active */ +#define ETH_MAC_TXFIFO_IDLE 0x00000000U /* Tx FIFO read status: Idle */ +#define ETH_MAC_TXFIFO_READ 0x00100000U /* Tx FIFO read status: Read (transferring data to the MAC transmitter) */ +#define ETH_MAC_TXFIFO_WAITING 0x00200000U /* Tx FIFO read status: Waiting for TxStatus from MAC transmitter */ +#define ETH_MAC_TXFIFO_WRITING 0x00300000U /* Tx FIFO read status: Writing the received TxStatus or flushing the TxFIFO */ +#define ETH_MAC_TRANSMISSION_PAUSE 0x00080000U /* MAC transmitter in pause */ +#define ETH_MAC_TRANSMITFRAMECONTROLLER_IDLE 0x00000000U /* MAC transmit frame controller: Idle */ +#define ETH_MAC_TRANSMITFRAMECONTROLLER_WAITING 0x00020000U /* MAC transmit frame controller: Waiting for Status of previous frame or IFG/backoff period to be over */ +#define ETH_MAC_TRANSMITFRAMECONTROLLER_GENRATING_PCF 0x00040000U /* MAC transmit frame controller: Generating and transmitting a Pause control frame (in full duplex mode) */ +#define ETH_MAC_TRANSMITFRAMECONTROLLER_TRANSFERRING 0x00060000U /* MAC transmit frame controller: Transferring input frame for transmission */ +#define ETH_MAC_MII_TRANSMIT_ACTIVE 0x00010000U /* MAC MII transmit engine active */ +#define ETH_MAC_RXFIFO_EMPTY 0x00000000U /* Rx FIFO fill level: empty */ +#define ETH_MAC_RXFIFO_BELOW_THRESHOLD 0x00000100U /* Rx FIFO fill level: fill-level below flow-control de-activate threshold */ +#define ETH_MAC_RXFIFO_ABOVE_THRESHOLD 0x00000200U /* Rx FIFO fill level: fill-level above flow-control activate threshold */ +#define ETH_MAC_RXFIFO_FULL 0x00000300U /* Rx FIFO fill level: full */ +#if defined(STM32F1) +#else +#define ETH_MAC_READCONTROLLER_IDLE 0x00000000U /* Rx FIFO read controller IDLE state */ +#define ETH_MAC_READCONTROLLER_READING_DATA 0x00000020U /* Rx FIFO read controller Reading frame data */ +#define ETH_MAC_READCONTROLLER_READING_STATUS 0x00000040U /* Rx FIFO read controller Reading frame status (or time-stamp) */ +#endif +#define ETH_MAC_READCONTROLLER_FLUSHING 0x00000060U /* Rx FIFO read controller Flushing the frame data and status */ +#define ETH_MAC_RXFIFO_WRITE_ACTIVE 0x00000010U /* Rx FIFO write controller active */ +#define ETH_MAC_SMALL_FIFO_NOTACTIVE 0x00000000U /* MAC small FIFO read / write controllers not active */ +#define ETH_MAC_SMALL_FIFO_READ_ACTIVE 0x00000002U /* MAC small FIFO read controller active */ +#define ETH_MAC_SMALL_FIFO_WRITE_ACTIVE 0x00000004U /* MAC small FIFO write controller active */ +#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */ +#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */ + +/** + * @} + */ + +/** @defgroup HAL_DCMI_Aliased_Defines HAL DCMI Aliased Defines maintained for legacy purpose + * @{ + */ +#define HAL_DCMI_ERROR_OVF HAL_DCMI_ERROR_OVR +#define DCMI_IT_OVF DCMI_IT_OVR +#define DCMI_FLAG_OVFRI DCMI_FLAG_OVRRI +#define DCMI_FLAG_OVFMI DCMI_FLAG_OVRMI + +#define HAL_DCMI_ConfigCROP HAL_DCMI_ConfigCrop +#define HAL_DCMI_EnableCROP HAL_DCMI_EnableCrop +#define HAL_DCMI_DisableCROP HAL_DCMI_DisableCrop + +/** + * @} + */ + +#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ + || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ + || defined(STM32H7) +/** @defgroup HAL_DMA2D_Aliased_Defines HAL DMA2D Aliased Defines maintained for legacy purpose + * @{ + */ +#define DMA2D_ARGB8888 DMA2D_OUTPUT_ARGB8888 +#define DMA2D_RGB888 DMA2D_OUTPUT_RGB888 +#define DMA2D_RGB565 DMA2D_OUTPUT_RGB565 +#define DMA2D_ARGB1555 DMA2D_OUTPUT_ARGB1555 +#define DMA2D_ARGB4444 DMA2D_OUTPUT_ARGB4444 + +#define CM_ARGB8888 DMA2D_INPUT_ARGB8888 +#define CM_RGB888 DMA2D_INPUT_RGB888 +#define CM_RGB565 DMA2D_INPUT_RGB565 +#define CM_ARGB1555 DMA2D_INPUT_ARGB1555 +#define CM_ARGB4444 DMA2D_INPUT_ARGB4444 +#define CM_L8 DMA2D_INPUT_L8 +#define CM_AL44 DMA2D_INPUT_AL44 +#define CM_AL88 DMA2D_INPUT_AL88 +#define CM_L4 DMA2D_INPUT_L4 +#define CM_A8 DMA2D_INPUT_A8 +#define CM_A4 DMA2D_INPUT_A4 +/** + * @} + */ +#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 */ + +#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ + || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ + || defined(STM32H7) || defined(STM32U5) +/** @defgroup DMA2D_Aliases DMA2D API Aliases + * @{ + */ +#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort + for compatibility with legacy code */ +/** + * @} + */ + +#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 || STM32U5 */ + +/** @defgroup HAL_PPP_Aliased_Defines HAL PPP Aliased Defines maintained for legacy purpose + * @{ + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup HAL_CRYP_Aliased_Functions HAL CRYP Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback +/** + * @} + */ + +/** @defgroup HAL_DCACHE_Aliased_Functions HAL DCACHE Aliased Functions maintained for legacy purpose + * @{ + */ + +#if defined(STM32U5) +#define HAL_DCACHE_CleanInvalidateByAddr HAL_DCACHE_CleanInvalidByAddr +#define HAL_DCACHE_CleanInvalidateByAddr_IT HAL_DCACHE_CleanInvalidByAddr_IT +#endif /* STM32U5 */ + +/** + * @} + */ + +#if !defined(STM32F2) +/** @defgroup HASH_alias HASH API alias + * @{ + */ +#define HAL_HASHEx_IRQHandler HAL_HASH_IRQHandler /*!< Redirection for compatibility with legacy code */ +/** + * + * @} + */ +#endif /* STM32F2 */ +/** @defgroup HAL_HASH_Aliased_Functions HAL HASH Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_HASH_STATETypeDef HAL_HASH_StateTypeDef +#define HAL_HASHPhaseTypeDef HAL_HASH_PhaseTypeDef +#define HAL_HMAC_MD5_Finish HAL_HASH_MD5_Finish +#define HAL_HMAC_SHA1_Finish HAL_HASH_SHA1_Finish +#define HAL_HMAC_SHA224_Finish HAL_HASH_SHA224_Finish +#define HAL_HMAC_SHA256_Finish HAL_HASH_SHA256_Finish + +/*HASH Algorithm Selection*/ + +#define HASH_AlgoSelection_SHA1 HASH_ALGOSELECTION_SHA1 +#define HASH_AlgoSelection_SHA224 HASH_ALGOSELECTION_SHA224 +#define HASH_AlgoSelection_SHA256 HASH_ALGOSELECTION_SHA256 +#define HASH_AlgoSelection_MD5 HASH_ALGOSELECTION_MD5 + +#define HASH_AlgoMode_HASH HASH_ALGOMODE_HASH +#define HASH_AlgoMode_HMAC HASH_ALGOMODE_HMAC + +#define HASH_HMACKeyType_ShortKey HASH_HMAC_KEYTYPE_SHORTKEY +#define HASH_HMACKeyType_LongKey HASH_HMAC_KEYTYPE_LONGKEY + +#if defined(STM32L4) || defined(STM32L5) || defined(STM32F2) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) + +#define HAL_HASH_MD5_Accumulate HAL_HASH_MD5_Accmlt +#define HAL_HASH_MD5_Accumulate_End HAL_HASH_MD5_Accmlt_End +#define HAL_HASH_MD5_Accumulate_IT HAL_HASH_MD5_Accmlt_IT +#define HAL_HASH_MD5_Accumulate_End_IT HAL_HASH_MD5_Accmlt_End_IT + +#define HAL_HASH_SHA1_Accumulate HAL_HASH_SHA1_Accmlt +#define HAL_HASH_SHA1_Accumulate_End HAL_HASH_SHA1_Accmlt_End +#define HAL_HASH_SHA1_Accumulate_IT HAL_HASH_SHA1_Accmlt_IT +#define HAL_HASH_SHA1_Accumulate_End_IT HAL_HASH_SHA1_Accmlt_End_IT + +#define HAL_HASHEx_SHA224_Accumulate HAL_HASHEx_SHA224_Accmlt +#define HAL_HASHEx_SHA224_Accumulate_End HAL_HASHEx_SHA224_Accmlt_End +#define HAL_HASHEx_SHA224_Accumulate_IT HAL_HASHEx_SHA224_Accmlt_IT +#define HAL_HASHEx_SHA224_Accumulate_End_IT HAL_HASHEx_SHA224_Accmlt_End_IT + +#define HAL_HASHEx_SHA256_Accumulate HAL_HASHEx_SHA256_Accmlt +#define HAL_HASHEx_SHA256_Accumulate_End HAL_HASHEx_SHA256_Accmlt_End +#define HAL_HASHEx_SHA256_Accumulate_IT HAL_HASHEx_SHA256_Accmlt_IT +#define HAL_HASHEx_SHA256_Accumulate_End_IT HAL_HASHEx_SHA256_Accmlt_End_IT + +#endif /* STM32L4 || STM32L5 || STM32F2 || STM32F4 || STM32F7 || STM32H7 */ +/** + * @} + */ + +/** @defgroup HAL_Aliased_Functions HAL Generic Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_EnableDBGSleepMode HAL_DBGMCU_EnableDBGSleepMode +#define HAL_DisableDBGSleepMode HAL_DBGMCU_DisableDBGSleepMode +#define HAL_EnableDBGStopMode HAL_DBGMCU_EnableDBGStopMode +#define HAL_DisableDBGStopMode HAL_DBGMCU_DisableDBGStopMode +#define HAL_EnableDBGStandbyMode HAL_DBGMCU_EnableDBGStandbyMode +#define HAL_DisableDBGStandbyMode HAL_DBGMCU_DisableDBGStandbyMode +#define HAL_DBG_LowPowerConfig(Periph, cmd) (((cmd\ + )==ENABLE)? HAL_DBGMCU_DBG_EnableLowPowerConfig(Periph) : HAL_DBGMCU_DBG_DisableLowPowerConfig(Periph)) +#define HAL_VREFINT_OutputSelect HAL_SYSCFG_VREFINT_OutputSelect +#define HAL_Lock_Cmd(cmd) (((cmd)==ENABLE) ? HAL_SYSCFG_Enable_Lock_VREFINT() : HAL_SYSCFG_Disable_Lock_VREFINT()) +#if defined(STM32L0) +#else +#define HAL_VREFINT_Cmd(cmd) (((cmd)==ENABLE)? HAL_SYSCFG_EnableVREFINT() : HAL_SYSCFG_DisableVREFINT()) +#endif +#define HAL_ADC_EnableBuffer_Cmd(cmd) (((cmd)==ENABLE) ? HAL_ADCEx_EnableVREFINT() : HAL_ADCEx_DisableVREFINT()) +#define HAL_ADC_EnableBufferSensor_Cmd(cmd) (((cmd\ + )==ENABLE) ? HAL_ADCEx_EnableVREFINTTempSensor() : HAL_ADCEx_DisableVREFINTTempSensor()) +#if defined(STM32H7A3xx) || defined(STM32H7B3xx) || defined(STM32H7B0xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xxQ) || defined(STM32H7B0xxQ) +#define HAL_EnableSRDomainDBGStopMode HAL_EnableDomain3DBGStopMode +#define HAL_DisableSRDomainDBGStopMode HAL_DisableDomain3DBGStopMode +#define HAL_EnableSRDomainDBGStandbyMode HAL_EnableDomain3DBGStandbyMode +#define HAL_DisableSRDomainDBGStandbyMode HAL_DisableDomain3DBGStandbyMode +#endif /* STM32H7A3xx || STM32H7B3xx || STM32H7B0xx || STM32H7A3xxQ || STM32H7B3xxQ || STM32H7B0xxQ */ + +/** + * @} + */ + +/** @defgroup HAL_FLASH_Aliased_Functions HAL FLASH Aliased Functions maintained for legacy purpose + * @{ + */ +#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram +#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown +#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown +#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock +#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock +#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase +#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program + +/** + * @} + */ + +/** @defgroup HAL_I2C_Aliased_Functions HAL I2C Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_I2CEx_AnalogFilter_Config HAL_I2CEx_ConfigAnalogFilter +#define HAL_I2CEx_DigitalFilter_Config HAL_I2CEx_ConfigDigitalFilter +#define HAL_FMPI2CEx_AnalogFilter_Config HAL_FMPI2CEx_ConfigAnalogFilter +#define HAL_FMPI2CEx_DigitalFilter_Config HAL_FMPI2CEx_ConfigDigitalFilter + +#define HAL_I2CFastModePlusConfig(SYSCFG_I2CFastModePlus, cmd) (((cmd\ + )==ENABLE)? HAL_I2CEx_EnableFastModePlus(SYSCFG_I2CFastModePlus): HAL_I2CEx_DisableFastModePlus(SYSCFG_I2CFastModePlus)) + +#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4) || defined(STM32L1) +#define HAL_I2C_Master_Sequential_Transmit_IT HAL_I2C_Master_Seq_Transmit_IT +#define HAL_I2C_Master_Sequential_Receive_IT HAL_I2C_Master_Seq_Receive_IT +#define HAL_I2C_Slave_Sequential_Transmit_IT HAL_I2C_Slave_Seq_Transmit_IT +#define HAL_I2C_Slave_Sequential_Receive_IT HAL_I2C_Slave_Seq_Receive_IT +#endif /* STM32H7 || STM32WB || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ +#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4)|| defined(STM32L1) +#define HAL_I2C_Master_Sequential_Transmit_DMA HAL_I2C_Master_Seq_Transmit_DMA +#define HAL_I2C_Master_Sequential_Receive_DMA HAL_I2C_Master_Seq_Receive_DMA +#define HAL_I2C_Slave_Sequential_Transmit_DMA HAL_I2C_Slave_Seq_Transmit_DMA +#define HAL_I2C_Slave_Sequential_Receive_DMA HAL_I2C_Slave_Seq_Receive_DMA +#endif /* STM32H7 || STM32WB || STM32G0 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ + +#if defined(STM32F4) +#define HAL_FMPI2C_Master_Sequential_Transmit_IT HAL_FMPI2C_Master_Seq_Transmit_IT +#define HAL_FMPI2C_Master_Sequential_Receive_IT HAL_FMPI2C_Master_Seq_Receive_IT +#define HAL_FMPI2C_Slave_Sequential_Transmit_IT HAL_FMPI2C_Slave_Seq_Transmit_IT +#define HAL_FMPI2C_Slave_Sequential_Receive_IT HAL_FMPI2C_Slave_Seq_Receive_IT +#define HAL_FMPI2C_Master_Sequential_Transmit_DMA HAL_FMPI2C_Master_Seq_Transmit_DMA +#define HAL_FMPI2C_Master_Sequential_Receive_DMA HAL_FMPI2C_Master_Seq_Receive_DMA +#define HAL_FMPI2C_Slave_Sequential_Transmit_DMA HAL_FMPI2C_Slave_Seq_Transmit_DMA +#define HAL_FMPI2C_Slave_Sequential_Receive_DMA HAL_FMPI2C_Slave_Seq_Receive_DMA +#endif /* STM32F4 */ +/** + * @} + */ + +/** @defgroup HAL_PWR_Aliased HAL PWR Aliased maintained for legacy purpose + * @{ + */ + +#if defined(STM32G0) +#define HAL_PWR_ConfigPVD HAL_PWREx_ConfigPVD +#define HAL_PWR_EnablePVD HAL_PWREx_EnablePVD +#define HAL_PWR_DisablePVD HAL_PWREx_DisablePVD +#define HAL_PWR_PVD_IRQHandler HAL_PWREx_PVD_IRQHandler +#endif +#define HAL_PWR_PVDConfig HAL_PWR_ConfigPVD +#define HAL_PWR_DisableBkUpReg HAL_PWREx_DisableBkUpReg +#define HAL_PWR_DisableFlashPowerDown HAL_PWREx_DisableFlashPowerDown +#define HAL_PWR_DisableVddio2Monitor HAL_PWREx_DisableVddio2Monitor +#define HAL_PWR_EnableBkUpReg HAL_PWREx_EnableBkUpReg +#define HAL_PWR_EnableFlashPowerDown HAL_PWREx_EnableFlashPowerDown +#define HAL_PWR_EnableVddio2Monitor HAL_PWREx_EnableVddio2Monitor +#define HAL_PWR_PVD_PVM_IRQHandler HAL_PWREx_PVD_PVM_IRQHandler +#define HAL_PWR_PVDLevelConfig HAL_PWR_ConfigPVD +#define HAL_PWR_Vddio2Monitor_IRQHandler HAL_PWREx_Vddio2Monitor_IRQHandler +#define HAL_PWR_Vddio2MonitorCallback HAL_PWREx_Vddio2MonitorCallback +#define HAL_PWREx_ActivateOverDrive HAL_PWREx_EnableOverDrive +#define HAL_PWREx_DeactivateOverDrive HAL_PWREx_DisableOverDrive +#define HAL_PWREx_DisableSDADCAnalog HAL_PWREx_DisableSDADC +#define HAL_PWREx_EnableSDADCAnalog HAL_PWREx_EnableSDADC +#define HAL_PWREx_PVMConfig HAL_PWREx_ConfigPVM + +#define PWR_MODE_NORMAL PWR_PVD_MODE_NORMAL +#define PWR_MODE_IT_RISING PWR_PVD_MODE_IT_RISING +#define PWR_MODE_IT_FALLING PWR_PVD_MODE_IT_FALLING +#define PWR_MODE_IT_RISING_FALLING PWR_PVD_MODE_IT_RISING_FALLING +#define PWR_MODE_EVENT_RISING PWR_PVD_MODE_EVENT_RISING +#define PWR_MODE_EVENT_FALLING PWR_PVD_MODE_EVENT_FALLING +#define PWR_MODE_EVENT_RISING_FALLING PWR_PVD_MODE_EVENT_RISING_FALLING + +#define CR_OFFSET_BB PWR_CR_OFFSET_BB +#define CSR_OFFSET_BB PWR_CSR_OFFSET_BB +#define PMODE_BIT_NUMBER VOS_BIT_NUMBER +#define CR_PMODE_BB CR_VOS_BB + +#define DBP_BitNumber DBP_BIT_NUMBER +#define PVDE_BitNumber PVDE_BIT_NUMBER +#define PMODE_BitNumber PMODE_BIT_NUMBER +#define EWUP_BitNumber EWUP_BIT_NUMBER +#define FPDS_BitNumber FPDS_BIT_NUMBER +#define ODEN_BitNumber ODEN_BIT_NUMBER +#define ODSWEN_BitNumber ODSWEN_BIT_NUMBER +#define MRLVDS_BitNumber MRLVDS_BIT_NUMBER +#define LPLVDS_BitNumber LPLVDS_BIT_NUMBER +#define BRE_BitNumber BRE_BIT_NUMBER + +#define PWR_MODE_EVT PWR_PVD_MODE_NORMAL + +#if defined (STM32U5) +#define PWR_SRAM1_PAGE1_STOP_RETENTION PWR_SRAM1_PAGE1_STOP +#define PWR_SRAM1_PAGE2_STOP_RETENTION PWR_SRAM1_PAGE2_STOP +#define PWR_SRAM1_PAGE3_STOP_RETENTION PWR_SRAM1_PAGE3_STOP +#define PWR_SRAM1_PAGE4_STOP_RETENTION PWR_SRAM1_PAGE4_STOP +#define PWR_SRAM1_PAGE5_STOP_RETENTION PWR_SRAM1_PAGE5_STOP +#define PWR_SRAM1_PAGE6_STOP_RETENTION PWR_SRAM1_PAGE6_STOP +#define PWR_SRAM1_PAGE7_STOP_RETENTION PWR_SRAM1_PAGE7_STOP +#define PWR_SRAM1_PAGE8_STOP_RETENTION PWR_SRAM1_PAGE8_STOP +#define PWR_SRAM1_PAGE9_STOP_RETENTION PWR_SRAM1_PAGE9_STOP +#define PWR_SRAM1_PAGE10_STOP_RETENTION PWR_SRAM1_PAGE10_STOP +#define PWR_SRAM1_PAGE11_STOP_RETENTION PWR_SRAM1_PAGE11_STOP +#define PWR_SRAM1_PAGE12_STOP_RETENTION PWR_SRAM1_PAGE12_STOP +#define PWR_SRAM1_FULL_STOP_RETENTION PWR_SRAM1_FULL_STOP + +#define PWR_SRAM2_PAGE1_STOP_RETENTION PWR_SRAM2_PAGE1_STOP +#define PWR_SRAM2_PAGE2_STOP_RETENTION PWR_SRAM2_PAGE2_STOP +#define PWR_SRAM2_FULL_STOP_RETENTION PWR_SRAM2_FULL_STOP + +#define PWR_SRAM3_PAGE1_STOP_RETENTION PWR_SRAM3_PAGE1_STOP +#define PWR_SRAM3_PAGE2_STOP_RETENTION PWR_SRAM3_PAGE2_STOP +#define PWR_SRAM3_PAGE3_STOP_RETENTION PWR_SRAM3_PAGE3_STOP +#define PWR_SRAM3_PAGE4_STOP_RETENTION PWR_SRAM3_PAGE4_STOP +#define PWR_SRAM3_PAGE5_STOP_RETENTION PWR_SRAM3_PAGE5_STOP +#define PWR_SRAM3_PAGE6_STOP_RETENTION PWR_SRAM3_PAGE6_STOP +#define PWR_SRAM3_PAGE7_STOP_RETENTION PWR_SRAM3_PAGE7_STOP +#define PWR_SRAM3_PAGE8_STOP_RETENTION PWR_SRAM3_PAGE8_STOP +#define PWR_SRAM3_PAGE9_STOP_RETENTION PWR_SRAM3_PAGE9_STOP +#define PWR_SRAM3_PAGE10_STOP_RETENTION PWR_SRAM3_PAGE10_STOP +#define PWR_SRAM3_PAGE11_STOP_RETENTION PWR_SRAM3_PAGE11_STOP +#define PWR_SRAM3_PAGE12_STOP_RETENTION PWR_SRAM3_PAGE12_STOP +#define PWR_SRAM3_PAGE13_STOP_RETENTION PWR_SRAM3_PAGE13_STOP +#define PWR_SRAM3_FULL_STOP_RETENTION PWR_SRAM3_FULL_STOP + +#define PWR_SRAM4_FULL_STOP_RETENTION PWR_SRAM4_FULL_STOP + +#define PWR_SRAM5_PAGE1_STOP_RETENTION PWR_SRAM5_PAGE1_STOP +#define PWR_SRAM5_PAGE2_STOP_RETENTION PWR_SRAM5_PAGE2_STOP +#define PWR_SRAM5_PAGE3_STOP_RETENTION PWR_SRAM5_PAGE3_STOP +#define PWR_SRAM5_PAGE4_STOP_RETENTION PWR_SRAM5_PAGE4_STOP +#define PWR_SRAM5_PAGE5_STOP_RETENTION PWR_SRAM5_PAGE5_STOP +#define PWR_SRAM5_PAGE6_STOP_RETENTION PWR_SRAM5_PAGE6_STOP +#define PWR_SRAM5_PAGE7_STOP_RETENTION PWR_SRAM5_PAGE7_STOP +#define PWR_SRAM5_PAGE8_STOP_RETENTION PWR_SRAM5_PAGE8_STOP +#define PWR_SRAM5_PAGE9_STOP_RETENTION PWR_SRAM5_PAGE9_STOP +#define PWR_SRAM5_PAGE10_STOP_RETENTION PWR_SRAM5_PAGE10_STOP +#define PWR_SRAM5_PAGE11_STOP_RETENTION PWR_SRAM5_PAGE11_STOP +#define PWR_SRAM5_PAGE12_STOP_RETENTION PWR_SRAM5_PAGE12_STOP +#define PWR_SRAM5_PAGE13_STOP_RETENTION PWR_SRAM5_PAGE13_STOP +#define PWR_SRAM5_FULL_STOP_RETENTION PWR_SRAM5_FULL_STOP + +#define PWR_ICACHE_FULL_STOP_RETENTION PWR_ICACHE_FULL_STOP +#define PWR_DCACHE1_FULL_STOP_RETENTION PWR_DCACHE1_FULL_STOP +#define PWR_DCACHE2_FULL_STOP_RETENTION PWR_DCACHE2_FULL_STOP +#define PWR_DMA2DRAM_FULL_STOP_RETENTION PWR_DMA2DRAM_FULL_STOP +#define PWR_PERIPHRAM_FULL_STOP_RETENTION PWR_PERIPHRAM_FULL_STOP +#define PWR_PKA32RAM_FULL_STOP_RETENTION PWR_PKA32RAM_FULL_STOP +#define PWR_GRAPHICPRAM_FULL_STOP_RETENTION PWR_GRAPHICPRAM_FULL_STOP +#define PWR_DSIRAM_FULL_STOP_RETENTION PWR_DSIRAM_FULL_STOP + +#define PWR_SRAM2_PAGE1_STANDBY_RETENTION PWR_SRAM2_PAGE1_STANDBY +#define PWR_SRAM2_PAGE2_STANDBY_RETENTION PWR_SRAM2_PAGE2_STANDBY +#define PWR_SRAM2_FULL_STANDBY_RETENTION PWR_SRAM2_FULL_STANDBY + +#define PWR_SRAM1_FULL_RUN_RETENTION PWR_SRAM1_FULL_RUN +#define PWR_SRAM2_FULL_RUN_RETENTION PWR_SRAM2_FULL_RUN +#define PWR_SRAM3_FULL_RUN_RETENTION PWR_SRAM3_FULL_RUN +#define PWR_SRAM4_FULL_RUN_RETENTION PWR_SRAM4_FULL_RUN +#define PWR_SRAM5_FULL_RUN_RETENTION PWR_SRAM5_FULL_RUN + +#define PWR_ALL_RAM_RUN_RETENTION_MASK PWR_ALL_RAM_RUN_MASK +#endif + +/** + * @} + */ + +/** @defgroup HAL_SMBUS_Aliased_Functions HAL SMBUS Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT +#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback +#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback +/** + * @} + */ + +/** @defgroup HAL_SPI_Aliased_Functions HAL SPI Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_SPI_FlushRxFifo HAL_SPIEx_FlushRxFifo +/** + * @} + */ + +/** @defgroup HAL_TIM_Aliased_Functions HAL TIM Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_TIM_DMADelayPulseCplt TIM_DMADelayPulseCplt +#define HAL_TIM_DMAError TIM_DMAError +#define HAL_TIM_DMACaptureCplt TIM_DMACaptureCplt +#define HAL_TIMEx_DMACommutationCplt TIMEx_DMACommutationCplt +#if defined(STM32H7) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) +#define HAL_TIM_SlaveConfigSynchronization HAL_TIM_SlaveConfigSynchro +#define HAL_TIM_SlaveConfigSynchronization_IT HAL_TIM_SlaveConfigSynchro_IT +#define HAL_TIMEx_CommutationCallback HAL_TIMEx_CommutCallback +#define HAL_TIMEx_ConfigCommutationEvent HAL_TIMEx_ConfigCommutEvent +#define HAL_TIMEx_ConfigCommutationEvent_IT HAL_TIMEx_ConfigCommutEvent_IT +#define HAL_TIMEx_ConfigCommutationEvent_DMA HAL_TIMEx_ConfigCommutEvent_DMA +#endif /* STM32H7 || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 */ +/** + * @} + */ + +/** @defgroup HAL_UART_Aliased_Functions HAL UART Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback +/** + * @} + */ + +/** @defgroup HAL_LTDC_Aliased_Functions HAL LTDC Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_LTDC_LineEvenCallback HAL_LTDC_LineEventCallback +#define HAL_LTDC_Relaod HAL_LTDC_Reload +#define HAL_LTDC_StructInitFromVideoConfig HAL_LTDCEx_StructInitFromVideoConfig +#define HAL_LTDC_StructInitFromAdaptedCommandConfig HAL_LTDCEx_StructInitFromAdaptedCommandConfig +/** + * @} + */ + + +/** @defgroup HAL_PPP_Aliased_Functions HAL PPP Aliased Functions maintained for legacy purpose + * @{ + */ + +/** + * @} + */ + +/* Exported macros ------------------------------------------------------------*/ + +/** @defgroup HAL_AES_Aliased_Macros HAL CRYP Aliased Macros maintained for legacy purpose + * @{ + */ +#define AES_IT_CC CRYP_IT_CC +#define AES_IT_ERR CRYP_IT_ERR +#define AES_FLAG_CCF CRYP_FLAG_CCF +/** + * @} + */ + +/** @defgroup HAL_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_GET_BOOT_MODE __HAL_SYSCFG_GET_BOOT_MODE +#define __HAL_REMAPMEMORY_FLASH __HAL_SYSCFG_REMAPMEMORY_FLASH +#define __HAL_REMAPMEMORY_SYSTEMFLASH __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH +#define __HAL_REMAPMEMORY_SRAM __HAL_SYSCFG_REMAPMEMORY_SRAM +#define __HAL_REMAPMEMORY_FMC __HAL_SYSCFG_REMAPMEMORY_FMC +#define __HAL_REMAPMEMORY_FMC_SDRAM __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM +#define __HAL_REMAPMEMORY_FSMC __HAL_SYSCFG_REMAPMEMORY_FSMC +#define __HAL_REMAPMEMORY_QUADSPI __HAL_SYSCFG_REMAPMEMORY_QUADSPI +#define __HAL_FMC_BANK __HAL_SYSCFG_FMC_BANK +#define __HAL_GET_FLAG __HAL_SYSCFG_GET_FLAG +#define __HAL_CLEAR_FLAG __HAL_SYSCFG_CLEAR_FLAG +#define __HAL_VREFINT_OUT_ENABLE __HAL_SYSCFG_VREFINT_OUT_ENABLE +#define __HAL_VREFINT_OUT_DISABLE __HAL_SYSCFG_VREFINT_OUT_DISABLE +#define __HAL_SYSCFG_SRAM2_WRP_ENABLE __HAL_SYSCFG_SRAM2_WRP_0_31_ENABLE + +#define SYSCFG_FLAG_VREF_READY SYSCFG_FLAG_VREFINT_READY +#define SYSCFG_FLAG_RC48 RCC_FLAG_HSI48 +#define IS_SYSCFG_FASTMODEPLUS_CONFIG IS_I2C_FASTMODEPLUS +#define UFB_MODE_BitNumber UFB_MODE_BIT_NUMBER +#define CMP_PD_BitNumber CMP_PD_BIT_NUMBER + +/** + * @} + */ + + +/** @defgroup HAL_ADC_Aliased_Macros HAL ADC Aliased Macros maintained for legacy purpose + * @{ + */ +#define __ADC_ENABLE __HAL_ADC_ENABLE +#define __ADC_DISABLE __HAL_ADC_DISABLE +#define __HAL_ADC_ENABLING_CONDITIONS ADC_ENABLING_CONDITIONS +#define __HAL_ADC_DISABLING_CONDITIONS ADC_DISABLING_CONDITIONS +#define __HAL_ADC_IS_ENABLED ADC_IS_ENABLE +#define __ADC_IS_ENABLED ADC_IS_ENABLE +#define __HAL_ADC_IS_SOFTWARE_START_REGULAR ADC_IS_SOFTWARE_START_REGULAR +#define __HAL_ADC_IS_SOFTWARE_START_INJECTED ADC_IS_SOFTWARE_START_INJECTED +#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED +#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR ADC_IS_CONVERSION_ONGOING_REGULAR +#define __HAL_ADC_IS_CONVERSION_ONGOING_INJECTED ADC_IS_CONVERSION_ONGOING_INJECTED +#define __HAL_ADC_IS_CONVERSION_ONGOING ADC_IS_CONVERSION_ONGOING +#define __HAL_ADC_CLEAR_ERRORCODE ADC_CLEAR_ERRORCODE + +#define __HAL_ADC_GET_RESOLUTION ADC_GET_RESOLUTION +#define __HAL_ADC_JSQR_RK ADC_JSQR_RK +#define __HAL_ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_SHIFT +#define __HAL_ADC_CFGR_AWD23CR ADC_CFGR_AWD23CR +#define __HAL_ADC_CFGR_INJECT_AUTO_CONVERSION ADC_CFGR_INJECT_AUTO_CONVERSION +#define __HAL_ADC_CFGR_INJECT_CONTEXT_QUEUE ADC_CFGR_INJECT_CONTEXT_QUEUE +#define __HAL_ADC_CFGR_INJECT_DISCCONTINUOUS ADC_CFGR_INJECT_DISCCONTINUOUS +#define __HAL_ADC_CFGR_REG_DISCCONTINUOUS ADC_CFGR_REG_DISCCONTINUOUS +#define __HAL_ADC_CFGR_DISCONTINUOUS_NUM ADC_CFGR_DISCONTINUOUS_NUM +#define __HAL_ADC_CFGR_AUTOWAIT ADC_CFGR_AUTOWAIT +#define __HAL_ADC_CFGR_CONTINUOUS ADC_CFGR_CONTINUOUS +#define __HAL_ADC_CFGR_OVERRUN ADC_CFGR_OVERRUN +#define __HAL_ADC_CFGR_DMACONTREQ ADC_CFGR_DMACONTREQ +#define __HAL_ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_SET +#define __HAL_ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_SET +#define __HAL_ADC_OFR_CHANNEL ADC_OFR_CHANNEL +#define __HAL_ADC_DIFSEL_CHANNEL ADC_DIFSEL_CHANNEL +#define __HAL_ADC_CALFACT_DIFF_SET ADC_CALFACT_DIFF_SET +#define __HAL_ADC_CALFACT_DIFF_GET ADC_CALFACT_DIFF_GET +#define __HAL_ADC_TRX_HIGHTHRESHOLD ADC_TRX_HIGHTHRESHOLD + +#define __HAL_ADC_OFFSET_SHIFT_RESOLUTION ADC_OFFSET_SHIFT_RESOLUTION +#define __HAL_ADC_AWD1THRESHOLD_SHIFT_RESOLUTION ADC_AWD1THRESHOLD_SHIFT_RESOLUTION +#define __HAL_ADC_AWD23THRESHOLD_SHIFT_RESOLUTION ADC_AWD23THRESHOLD_SHIFT_RESOLUTION +#define __HAL_ADC_COMMON_REGISTER ADC_COMMON_REGISTER +#define __HAL_ADC_COMMON_CCR_MULTI ADC_COMMON_CCR_MULTI +#define __HAL_ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE +#define __ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE +#define __HAL_ADC_NONMULTIMODE_OR_MULTIMODEMASTER ADC_NONMULTIMODE_OR_MULTIMODEMASTER +#define __HAL_ADC_COMMON_ADC_OTHER ADC_COMMON_ADC_OTHER +#define __HAL_ADC_MULTI_SLAVE ADC_MULTI_SLAVE + +#define __HAL_ADC_SQR1_L ADC_SQR1_L_SHIFT +#define __HAL_ADC_JSQR_JL ADC_JSQR_JL_SHIFT +#define __HAL_ADC_JSQR_RK_JL ADC_JSQR_RK_JL +#define __HAL_ADC_CR1_DISCONTINUOUS_NUM ADC_CR1_DISCONTINUOUS_NUM +#define __HAL_ADC_CR1_SCAN ADC_CR1_SCAN_SET +#define __HAL_ADC_CONVCYCLES_MAX_RANGE ADC_CONVCYCLES_MAX_RANGE +#define __HAL_ADC_CLOCK_PRESCALER_RANGE ADC_CLOCK_PRESCALER_RANGE +#define __HAL_ADC_GET_CLOCK_PRESCALER ADC_GET_CLOCK_PRESCALER + +#define __HAL_ADC_SQR1 ADC_SQR1 +#define __HAL_ADC_SMPR1 ADC_SMPR1 +#define __HAL_ADC_SMPR2 ADC_SMPR2 +#define __HAL_ADC_SQR3_RK ADC_SQR3_RK +#define __HAL_ADC_SQR2_RK ADC_SQR2_RK +#define __HAL_ADC_SQR1_RK ADC_SQR1_RK +#define __HAL_ADC_CR2_CONTINUOUS ADC_CR2_CONTINUOUS +#define __HAL_ADC_CR1_DISCONTINUOUS ADC_CR1_DISCONTINUOUS +#define __HAL_ADC_CR1_SCANCONV ADC_CR1_SCANCONV +#define __HAL_ADC_CR2_EOCSelection ADC_CR2_EOCSelection +#define __HAL_ADC_CR2_DMAContReq ADC_CR2_DMAContReq +#define __HAL_ADC_JSQR ADC_JSQR + +#define __HAL_ADC_CHSELR_CHANNEL ADC_CHSELR_CHANNEL +#define __HAL_ADC_CFGR1_REG_DISCCONTINUOUS ADC_CFGR1_REG_DISCCONTINUOUS +#define __HAL_ADC_CFGR1_AUTOOFF ADC_CFGR1_AUTOOFF +#define __HAL_ADC_CFGR1_AUTOWAIT ADC_CFGR1_AUTOWAIT +#define __HAL_ADC_CFGR1_CONTINUOUS ADC_CFGR1_CONTINUOUS +#define __HAL_ADC_CFGR1_OVERRUN ADC_CFGR1_OVERRUN +#define __HAL_ADC_CFGR1_SCANDIR ADC_CFGR1_SCANDIR +#define __HAL_ADC_CFGR1_DMACONTREQ ADC_CFGR1_DMACONTREQ + +/** + * @} + */ + +/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_DHR12R1_ALIGNEMENT DAC_DHR12R1_ALIGNMENT +#define __HAL_DHR12R2_ALIGNEMENT DAC_DHR12R2_ALIGNMENT +#define __HAL_DHR12RD_ALIGNEMENT DAC_DHR12RD_ALIGNMENT +#define IS_DAC_GENERATE_WAVE IS_DAC_WAVE + +/** + * @} + */ + +/** @defgroup HAL_DBGMCU_Aliased_Macros HAL DBGMCU Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_FREEZE_TIM1_DBGMCU __HAL_DBGMCU_FREEZE_TIM1 +#define __HAL_UNFREEZE_TIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM1 +#define __HAL_FREEZE_TIM2_DBGMCU __HAL_DBGMCU_FREEZE_TIM2 +#define __HAL_UNFREEZE_TIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM2 +#define __HAL_FREEZE_TIM3_DBGMCU __HAL_DBGMCU_FREEZE_TIM3 +#define __HAL_UNFREEZE_TIM3_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM3 +#define __HAL_FREEZE_TIM4_DBGMCU __HAL_DBGMCU_FREEZE_TIM4 +#define __HAL_UNFREEZE_TIM4_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM4 +#define __HAL_FREEZE_TIM5_DBGMCU __HAL_DBGMCU_FREEZE_TIM5 +#define __HAL_UNFREEZE_TIM5_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM5 +#define __HAL_FREEZE_TIM6_DBGMCU __HAL_DBGMCU_FREEZE_TIM6 +#define __HAL_UNFREEZE_TIM6_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM6 +#define __HAL_FREEZE_TIM7_DBGMCU __HAL_DBGMCU_FREEZE_TIM7 +#define __HAL_UNFREEZE_TIM7_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM7 +#define __HAL_FREEZE_TIM8_DBGMCU __HAL_DBGMCU_FREEZE_TIM8 +#define __HAL_UNFREEZE_TIM8_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM8 + +#define __HAL_FREEZE_TIM9_DBGMCU __HAL_DBGMCU_FREEZE_TIM9 +#define __HAL_UNFREEZE_TIM9_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM9 +#define __HAL_FREEZE_TIM10_DBGMCU __HAL_DBGMCU_FREEZE_TIM10 +#define __HAL_UNFREEZE_TIM10_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM10 +#define __HAL_FREEZE_TIM11_DBGMCU __HAL_DBGMCU_FREEZE_TIM11 +#define __HAL_UNFREEZE_TIM11_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM11 +#define __HAL_FREEZE_TIM12_DBGMCU __HAL_DBGMCU_FREEZE_TIM12 +#define __HAL_UNFREEZE_TIM12_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM12 +#define __HAL_FREEZE_TIM13_DBGMCU __HAL_DBGMCU_FREEZE_TIM13 +#define __HAL_UNFREEZE_TIM13_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM13 +#define __HAL_FREEZE_TIM14_DBGMCU __HAL_DBGMCU_FREEZE_TIM14 +#define __HAL_UNFREEZE_TIM14_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM14 +#define __HAL_FREEZE_CAN2_DBGMCU __HAL_DBGMCU_FREEZE_CAN2 +#define __HAL_UNFREEZE_CAN2_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN2 + + +#define __HAL_FREEZE_TIM15_DBGMCU __HAL_DBGMCU_FREEZE_TIM15 +#define __HAL_UNFREEZE_TIM15_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM15 +#define __HAL_FREEZE_TIM16_DBGMCU __HAL_DBGMCU_FREEZE_TIM16 +#define __HAL_UNFREEZE_TIM16_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM16 +#define __HAL_FREEZE_TIM17_DBGMCU __HAL_DBGMCU_FREEZE_TIM17 +#define __HAL_UNFREEZE_TIM17_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM17 +#define __HAL_FREEZE_RTC_DBGMCU __HAL_DBGMCU_FREEZE_RTC +#define __HAL_UNFREEZE_RTC_DBGMCU __HAL_DBGMCU_UNFREEZE_RTC +#if defined(STM32H7) +#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG1 +#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UnFreeze_WWDG1 +#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG1 +#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UnFreeze_IWDG1 +#else +#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG +#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_WWDG +#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG +#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_IWDG +#endif /* STM32H7 */ +#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT +#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT +#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT +#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT +#define __HAL_FREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT +#define __HAL_UNFREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT +#define __HAL_FREEZE_CAN1_DBGMCU __HAL_DBGMCU_FREEZE_CAN1 +#define __HAL_UNFREEZE_CAN1_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN1 +#define __HAL_FREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM1 +#define __HAL_UNFREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM1 +#define __HAL_FREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM2 +#define __HAL_UNFREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM2 + +/** + * @} + */ + +/** @defgroup HAL_COMP_Aliased_Macros HAL COMP Aliased Macros maintained for legacy purpose + * @{ + */ +#if defined(STM32F3) +#define COMP_START __HAL_COMP_ENABLE +#define COMP_STOP __HAL_COMP_DISABLE +#define COMP_LOCK __HAL_COMP_LOCK + +#if defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) +#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_IT()) +#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_IT()) +#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ + __HAL_COMP_COMP6_EXTI_GET_FLAG()) +#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ + __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) +# endif +# if defined(STM32F302xE) || defined(STM32F302xC) +#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ + __HAL_COMP_COMP6_EXTI_ENABLE_IT()) +#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ + __HAL_COMP_COMP6_EXTI_DISABLE_IT()) +#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ + __HAL_COMP_COMP6_EXTI_GET_FLAG()) +#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ + __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) +# endif +# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx) +#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE() : \ + __HAL_COMP_COMP7_EXTI_ENABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_RISING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE() : \ + __HAL_COMP_COMP7_EXTI_DISABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP7_EXTI_ENABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_FALLING_EDGE() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP7_EXTI_DISABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_IT() : \ + __HAL_COMP_COMP7_EXTI_ENABLE_IT()) +#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_IT() : \ + ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_IT() : \ + __HAL_COMP_COMP7_EXTI_DISABLE_IT()) +#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_GET_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_GET_FLAG() : \ + __HAL_COMP_COMP7_EXTI_GET_FLAG()) +#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \ + ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \ + __HAL_COMP_COMP7_EXTI_CLEAR_FLAG()) +# endif +# if defined(STM32F373xC) ||defined(STM32F378xx) +#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_IT()) +#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_IT()) +#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ + __HAL_COMP_COMP2_EXTI_GET_FLAG()) +#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ + __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) +# endif +#else +#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) +#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ + __HAL_COMP_COMP2_EXTI_ENABLE_IT()) +#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ + __HAL_COMP_COMP2_EXTI_DISABLE_IT()) +#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ + __HAL_COMP_COMP2_EXTI_GET_FLAG()) +#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ + __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) +#endif + +#define __HAL_COMP_GET_EXTI_LINE COMP_GET_EXTI_LINE + +#if defined(STM32L0) || defined(STM32L4) +/* Note: On these STM32 families, the only argument of this macro */ +/* is COMP_FLAG_LOCK. */ +/* This macro is replaced by __HAL_COMP_IS_LOCKED with only HAL handle */ +/* argument. */ +#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (__HAL_COMP_IS_LOCKED(__HANDLE__)) +#endif +/** + * @} + */ + +#if defined(STM32L0) || defined(STM32L4) +/** @defgroup HAL_COMP_Aliased_Functions HAL COMP Aliased Functions maintained for legacy purpose + * @{ + */ +#define HAL_COMP_Start_IT HAL_COMP_Start /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ +#define HAL_COMP_Stop_IT HAL_COMP_Stop /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ +/** + * @} + */ +#endif + +/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose + * @{ + */ + +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_WAVE_NONE) || \ + ((WAVE) == DAC_WAVE_NOISE)|| \ + ((WAVE) == DAC_WAVE_TRIANGLE)) + +/** + * @} + */ + +/** @defgroup HAL_FLASH_Aliased_Macros HAL FLASH Aliased Macros maintained for legacy purpose + * @{ + */ + +#define IS_WRPAREA IS_OB_WRPAREA +#define IS_TYPEPROGRAM IS_FLASH_TYPEPROGRAM +#define IS_TYPEPROGRAMFLASH IS_FLASH_TYPEPROGRAM +#define IS_TYPEERASE IS_FLASH_TYPEERASE +#define IS_NBSECTORS IS_FLASH_NBSECTORS +#define IS_OB_WDG_SOURCE IS_OB_IWDG_SOURCE + +/** + * @} + */ + +/** @defgroup HAL_I2C_Aliased_Macros HAL I2C Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __HAL_I2C_RESET_CR2 I2C_RESET_CR2 +#define __HAL_I2C_GENERATE_START I2C_GENERATE_START +#if defined(STM32F1) +#define __HAL_I2C_FREQ_RANGE I2C_FREQRANGE +#else +#define __HAL_I2C_FREQ_RANGE I2C_FREQ_RANGE +#endif /* STM32F1 */ +#define __HAL_I2C_RISE_TIME I2C_RISE_TIME +#define __HAL_I2C_SPEED_STANDARD I2C_SPEED_STANDARD +#define __HAL_I2C_SPEED_FAST I2C_SPEED_FAST +#define __HAL_I2C_SPEED I2C_SPEED +#define __HAL_I2C_7BIT_ADD_WRITE I2C_7BIT_ADD_WRITE +#define __HAL_I2C_7BIT_ADD_READ I2C_7BIT_ADD_READ +#define __HAL_I2C_10BIT_ADDRESS I2C_10BIT_ADDRESS +#define __HAL_I2C_10BIT_HEADER_WRITE I2C_10BIT_HEADER_WRITE +#define __HAL_I2C_10BIT_HEADER_READ I2C_10BIT_HEADER_READ +#define __HAL_I2C_MEM_ADD_MSB I2C_MEM_ADD_MSB +#define __HAL_I2C_MEM_ADD_LSB I2C_MEM_ADD_LSB +#define __HAL_I2C_FREQRANGE I2C_FREQRANGE +/** + * @} + */ + +/** @defgroup HAL_I2S_Aliased_Macros HAL I2S Aliased Macros maintained for legacy purpose + * @{ + */ + +#define IS_I2S_INSTANCE IS_I2S_ALL_INSTANCE +#define IS_I2S_INSTANCE_EXT IS_I2S_ALL_INSTANCE_EXT + +#if defined(STM32H7) +#define __HAL_I2S_CLEAR_FREFLAG __HAL_I2S_CLEAR_TIFREFLAG +#endif + +/** + * @} + */ + +/** @defgroup HAL_IRDA_Aliased_Macros HAL IRDA Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __IRDA_DISABLE __HAL_IRDA_DISABLE +#define __IRDA_ENABLE __HAL_IRDA_ENABLE + +#define __HAL_IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE +#define __HAL_IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION +#define __IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE +#define __IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION + +#define IS_IRDA_ONEBIT_SAMPLE IS_IRDA_ONE_BIT_SAMPLE + + +/** + * @} + */ + + +/** @defgroup HAL_IWDG_Aliased_Macros HAL IWDG Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_IWDG_ENABLE_WRITE_ACCESS IWDG_ENABLE_WRITE_ACCESS +#define __HAL_IWDG_DISABLE_WRITE_ACCESS IWDG_DISABLE_WRITE_ACCESS +/** + * @} + */ + + +/** @defgroup HAL_LPTIM_Aliased_Macros HAL LPTIM Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __HAL_LPTIM_ENABLE_INTERRUPT __HAL_LPTIM_ENABLE_IT +#define __HAL_LPTIM_DISABLE_INTERRUPT __HAL_LPTIM_DISABLE_IT +#define __HAL_LPTIM_GET_ITSTATUS __HAL_LPTIM_GET_IT_SOURCE + +/** + * @} + */ + + +/** @defgroup HAL_OPAMP_Aliased_Macros HAL OPAMP Aliased Macros maintained for legacy purpose + * @{ + */ +#define __OPAMP_CSR_OPAXPD OPAMP_CSR_OPAXPD +#define __OPAMP_CSR_S3SELX OPAMP_CSR_S3SELX +#define __OPAMP_CSR_S4SELX OPAMP_CSR_S4SELX +#define __OPAMP_CSR_S5SELX OPAMP_CSR_S5SELX +#define __OPAMP_CSR_S6SELX OPAMP_CSR_S6SELX +#define __OPAMP_CSR_OPAXCAL_L OPAMP_CSR_OPAXCAL_L +#define __OPAMP_CSR_OPAXCAL_H OPAMP_CSR_OPAXCAL_H +#define __OPAMP_CSR_OPAXLPM OPAMP_CSR_OPAXLPM +#define __OPAMP_CSR_ALL_SWITCHES OPAMP_CSR_ALL_SWITCHES +#define __OPAMP_CSR_ANAWSELX OPAMP_CSR_ANAWSELX +#define __OPAMP_CSR_OPAXCALOUT OPAMP_CSR_OPAXCALOUT +#define __OPAMP_OFFSET_TRIM_BITSPOSITION OPAMP_OFFSET_TRIM_BITSPOSITION +#define __OPAMP_OFFSET_TRIM_SET OPAMP_OFFSET_TRIM_SET + +/** + * @} + */ + + +/** @defgroup HAL_PWR_Aliased_Macros HAL PWR Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_PVD_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT +#define __HAL_PVD_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT +#define __HAL_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE +#define __HAL_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE +#define __HAL_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE +#define __HAL_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE +#define __HAL_PVM_EVENT_DISABLE __HAL_PWR_PVM_EVENT_DISABLE +#define __HAL_PVM_EVENT_ENABLE __HAL_PWR_PVM_EVENT_ENABLE +#define __HAL_PVM_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_DISABLE +#define __HAL_PVM_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_ENABLE +#define __HAL_PVM_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_DISABLE +#define __HAL_PVM_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_ENABLE +#define __HAL_PWR_INTERNALWAKEUP_DISABLE HAL_PWREx_DisableInternalWakeUpLine +#define __HAL_PWR_INTERNALWAKEUP_ENABLE HAL_PWREx_EnableInternalWakeUpLine +#define __HAL_PWR_PULL_UP_DOWN_CONFIG_DISABLE HAL_PWREx_DisablePullUpPullDownConfig +#define __HAL_PWR_PULL_UP_DOWN_CONFIG_ENABLE HAL_PWREx_EnablePullUpPullDownConfig +#define __HAL_PWR_PVD_EXTI_CLEAR_EGDE_TRIGGER() do { __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); } while(0) +#define __HAL_PWR_PVD_EXTI_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT +#define __HAL_PWR_PVD_EXTI_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT +#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE +#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE +#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE +#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE +#define __HAL_PWR_PVD_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE +#define __HAL_PWR_PVD_EXTI_SET_RISING_EDGE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE +#define __HAL_PWR_PVM_DISABLE() do { HAL_PWREx_DisablePVM1();HAL_PWREx_DisablePVM2();HAL_PWREx_DisablePVM3();HAL_PWREx_DisablePVM4(); } while(0) +#define __HAL_PWR_PVM_ENABLE() do { HAL_PWREx_EnablePVM1();HAL_PWREx_EnablePVM2();HAL_PWREx_EnablePVM3();HAL_PWREx_EnablePVM4(); } while(0) +#define __HAL_PWR_SRAM2CONTENT_PRESERVE_DISABLE HAL_PWREx_DisableSRAM2ContentRetention +#define __HAL_PWR_SRAM2CONTENT_PRESERVE_ENABLE HAL_PWREx_EnableSRAM2ContentRetention +#define __HAL_PWR_VDDIO2_DISABLE HAL_PWREx_DisableVddIO2 +#define __HAL_PWR_VDDIO2_ENABLE HAL_PWREx_EnableVddIO2 +#define __HAL_PWR_VDDIO2_EXTI_CLEAR_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE +#define __HAL_PWR_VDDIO2_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE +#define __HAL_PWR_VDDUSB_DISABLE HAL_PWREx_DisableVddUSB +#define __HAL_PWR_VDDUSB_ENABLE HAL_PWREx_EnableVddUSB + +#if defined (STM32F4) +#define __HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_ENABLE_IT() +#define __HAL_PVD_EXTI_DISABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_DISABLE_IT() +#define __HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GET_FLAG() +#define __HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_CLEAR_FLAG() +#define __HAL_PVD_EXTI_GENERATE_SWIT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GENERATE_SWIT() +#else +#define __HAL_PVD_EXTI_CLEAR_FLAG __HAL_PWR_PVD_EXTI_CLEAR_FLAG +#define __HAL_PVD_EXTI_DISABLE_IT __HAL_PWR_PVD_EXTI_DISABLE_IT +#define __HAL_PVD_EXTI_ENABLE_IT __HAL_PWR_PVD_EXTI_ENABLE_IT +#define __HAL_PVD_EXTI_GENERATE_SWIT __HAL_PWR_PVD_EXTI_GENERATE_SWIT +#define __HAL_PVD_EXTI_GET_FLAG __HAL_PWR_PVD_EXTI_GET_FLAG +#endif /* STM32F4 */ +/** + * @} + */ + + +/** @defgroup HAL_RCC_Aliased HAL RCC Aliased maintained for legacy purpose + * @{ + */ + +#define RCC_StopWakeUpClock_MSI RCC_STOP_WAKEUPCLOCK_MSI +#define RCC_StopWakeUpClock_HSI RCC_STOP_WAKEUPCLOCK_HSI + +#define HAL_RCC_CCSCallback HAL_RCC_CSSCallback +#define HAL_RC48_EnableBuffer_Cmd(cmd) (((cmd\ + )==ENABLE) ? HAL_RCCEx_EnableHSI48_VREFINT() : HAL_RCCEx_DisableHSI48_VREFINT()) + +#define __ADC_CLK_DISABLE __HAL_RCC_ADC_CLK_DISABLE +#define __ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE +#define __ADC_CLK_SLEEP_DISABLE __HAL_RCC_ADC_CLK_SLEEP_DISABLE +#define __ADC_CLK_SLEEP_ENABLE __HAL_RCC_ADC_CLK_SLEEP_ENABLE +#define __ADC_FORCE_RESET __HAL_RCC_ADC_FORCE_RESET +#define __ADC_RELEASE_RESET __HAL_RCC_ADC_RELEASE_RESET +#define __ADC1_CLK_DISABLE __HAL_RCC_ADC1_CLK_DISABLE +#define __ADC1_CLK_ENABLE __HAL_RCC_ADC1_CLK_ENABLE +#define __ADC1_FORCE_RESET __HAL_RCC_ADC1_FORCE_RESET +#define __ADC1_RELEASE_RESET __HAL_RCC_ADC1_RELEASE_RESET +#define __ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC1_CLK_SLEEP_ENABLE +#define __ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC1_CLK_SLEEP_DISABLE +#define __ADC2_CLK_DISABLE __HAL_RCC_ADC2_CLK_DISABLE +#define __ADC2_CLK_ENABLE __HAL_RCC_ADC2_CLK_ENABLE +#define __ADC2_FORCE_RESET __HAL_RCC_ADC2_FORCE_RESET +#define __ADC2_RELEASE_RESET __HAL_RCC_ADC2_RELEASE_RESET +#define __ADC3_CLK_DISABLE __HAL_RCC_ADC3_CLK_DISABLE +#define __ADC3_CLK_ENABLE __HAL_RCC_ADC3_CLK_ENABLE +#define __ADC3_FORCE_RESET __HAL_RCC_ADC3_FORCE_RESET +#define __ADC3_RELEASE_RESET __HAL_RCC_ADC3_RELEASE_RESET +#define __AES_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE +#define __AES_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE +#define __AES_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE +#define __AES_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE +#define __AES_FORCE_RESET __HAL_RCC_AES_FORCE_RESET +#define __AES_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET +#define __CRYP_CLK_SLEEP_ENABLE __HAL_RCC_CRYP_CLK_SLEEP_ENABLE +#define __CRYP_CLK_SLEEP_DISABLE __HAL_RCC_CRYP_CLK_SLEEP_DISABLE +#define __CRYP_CLK_ENABLE __HAL_RCC_CRYP_CLK_ENABLE +#define __CRYP_CLK_DISABLE __HAL_RCC_CRYP_CLK_DISABLE +#define __CRYP_FORCE_RESET __HAL_RCC_CRYP_FORCE_RESET +#define __CRYP_RELEASE_RESET __HAL_RCC_CRYP_RELEASE_RESET +#define __AFIO_CLK_DISABLE __HAL_RCC_AFIO_CLK_DISABLE +#define __AFIO_CLK_ENABLE __HAL_RCC_AFIO_CLK_ENABLE +#define __AFIO_FORCE_RESET __HAL_RCC_AFIO_FORCE_RESET +#define __AFIO_RELEASE_RESET __HAL_RCC_AFIO_RELEASE_RESET +#define __AHB_FORCE_RESET __HAL_RCC_AHB_FORCE_RESET +#define __AHB_RELEASE_RESET __HAL_RCC_AHB_RELEASE_RESET +#define __AHB1_FORCE_RESET __HAL_RCC_AHB1_FORCE_RESET +#define __AHB1_RELEASE_RESET __HAL_RCC_AHB1_RELEASE_RESET +#define __AHB2_FORCE_RESET __HAL_RCC_AHB2_FORCE_RESET +#define __AHB2_RELEASE_RESET __HAL_RCC_AHB2_RELEASE_RESET +#define __AHB3_FORCE_RESET __HAL_RCC_AHB3_FORCE_RESET +#define __AHB3_RELEASE_RESET __HAL_RCC_AHB3_RELEASE_RESET +#define __APB1_FORCE_RESET __HAL_RCC_APB1_FORCE_RESET +#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET +#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET +#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET +#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE +#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE +#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET +#define __BKP_RELEASE_RESET __HAL_RCC_BKP_RELEASE_RESET +#define __CAN1_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE +#define __CAN1_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE +#define __CAN1_CLK_SLEEP_DISABLE __HAL_RCC_CAN1_CLK_SLEEP_DISABLE +#define __CAN1_CLK_SLEEP_ENABLE __HAL_RCC_CAN1_CLK_SLEEP_ENABLE +#define __CAN1_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET +#define __CAN1_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET +#define __CAN_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE +#define __CAN_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE +#define __CAN_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET +#define __CAN_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET +#define __CAN2_CLK_DISABLE __HAL_RCC_CAN2_CLK_DISABLE +#define __CAN2_CLK_ENABLE __HAL_RCC_CAN2_CLK_ENABLE +#define __CAN2_FORCE_RESET __HAL_RCC_CAN2_FORCE_RESET +#define __CAN2_RELEASE_RESET __HAL_RCC_CAN2_RELEASE_RESET +#define __CEC_CLK_DISABLE __HAL_RCC_CEC_CLK_DISABLE +#define __CEC_CLK_ENABLE __HAL_RCC_CEC_CLK_ENABLE +#define __COMP_CLK_DISABLE __HAL_RCC_COMP_CLK_DISABLE +#define __COMP_CLK_ENABLE __HAL_RCC_COMP_CLK_ENABLE +#define __COMP_FORCE_RESET __HAL_RCC_COMP_FORCE_RESET +#define __COMP_RELEASE_RESET __HAL_RCC_COMP_RELEASE_RESET +#define __COMP_CLK_SLEEP_ENABLE __HAL_RCC_COMP_CLK_SLEEP_ENABLE +#define __COMP_CLK_SLEEP_DISABLE __HAL_RCC_COMP_CLK_SLEEP_DISABLE +#define __CEC_FORCE_RESET __HAL_RCC_CEC_FORCE_RESET +#define __CEC_RELEASE_RESET __HAL_RCC_CEC_RELEASE_RESET +#define __CRC_CLK_DISABLE __HAL_RCC_CRC_CLK_DISABLE +#define __CRC_CLK_ENABLE __HAL_RCC_CRC_CLK_ENABLE +#define __CRC_CLK_SLEEP_DISABLE __HAL_RCC_CRC_CLK_SLEEP_DISABLE +#define __CRC_CLK_SLEEP_ENABLE __HAL_RCC_CRC_CLK_SLEEP_ENABLE +#define __CRC_FORCE_RESET __HAL_RCC_CRC_FORCE_RESET +#define __CRC_RELEASE_RESET __HAL_RCC_CRC_RELEASE_RESET +#define __DAC_CLK_DISABLE __HAL_RCC_DAC_CLK_DISABLE +#define __DAC_CLK_ENABLE __HAL_RCC_DAC_CLK_ENABLE +#define __DAC_FORCE_RESET __HAL_RCC_DAC_FORCE_RESET +#define __DAC_RELEASE_RESET __HAL_RCC_DAC_RELEASE_RESET +#define __DAC1_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE +#define __DAC1_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE +#define __DAC1_CLK_SLEEP_DISABLE __HAL_RCC_DAC1_CLK_SLEEP_DISABLE +#define __DAC1_CLK_SLEEP_ENABLE __HAL_RCC_DAC1_CLK_SLEEP_ENABLE +#define __DAC1_FORCE_RESET __HAL_RCC_DAC1_FORCE_RESET +#define __DAC1_RELEASE_RESET __HAL_RCC_DAC1_RELEASE_RESET +#define __DBGMCU_CLK_ENABLE __HAL_RCC_DBGMCU_CLK_ENABLE +#define __DBGMCU_CLK_DISABLE __HAL_RCC_DBGMCU_CLK_DISABLE +#define __DBGMCU_FORCE_RESET __HAL_RCC_DBGMCU_FORCE_RESET +#define __DBGMCU_RELEASE_RESET __HAL_RCC_DBGMCU_RELEASE_RESET +#define __DFSDM_CLK_DISABLE __HAL_RCC_DFSDM_CLK_DISABLE +#define __DFSDM_CLK_ENABLE __HAL_RCC_DFSDM_CLK_ENABLE +#define __DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE +#define __DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE +#define __DFSDM_FORCE_RESET __HAL_RCC_DFSDM_FORCE_RESET +#define __DFSDM_RELEASE_RESET __HAL_RCC_DFSDM_RELEASE_RESET +#define __DMA1_CLK_DISABLE __HAL_RCC_DMA1_CLK_DISABLE +#define __DMA1_CLK_ENABLE __HAL_RCC_DMA1_CLK_ENABLE +#define __DMA1_CLK_SLEEP_DISABLE __HAL_RCC_DMA1_CLK_SLEEP_DISABLE +#define __DMA1_CLK_SLEEP_ENABLE __HAL_RCC_DMA1_CLK_SLEEP_ENABLE +#define __DMA1_FORCE_RESET __HAL_RCC_DMA1_FORCE_RESET +#define __DMA1_RELEASE_RESET __HAL_RCC_DMA1_RELEASE_RESET +#define __DMA2_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE +#define __DMA2_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE +#define __DMA2_CLK_SLEEP_DISABLE __HAL_RCC_DMA2_CLK_SLEEP_DISABLE +#define __DMA2_CLK_SLEEP_ENABLE __HAL_RCC_DMA2_CLK_SLEEP_ENABLE +#define __DMA2_FORCE_RESET __HAL_RCC_DMA2_FORCE_RESET +#define __DMA2_RELEASE_RESET __HAL_RCC_DMA2_RELEASE_RESET +#define __ETHMAC_CLK_DISABLE __HAL_RCC_ETHMAC_CLK_DISABLE +#define __ETHMAC_CLK_ENABLE __HAL_RCC_ETHMAC_CLK_ENABLE +#define __ETHMAC_FORCE_RESET __HAL_RCC_ETHMAC_FORCE_RESET +#define __ETHMAC_RELEASE_RESET __HAL_RCC_ETHMAC_RELEASE_RESET +#define __ETHMACRX_CLK_DISABLE __HAL_RCC_ETHMACRX_CLK_DISABLE +#define __ETHMACRX_CLK_ENABLE __HAL_RCC_ETHMACRX_CLK_ENABLE +#define __ETHMACTX_CLK_DISABLE __HAL_RCC_ETHMACTX_CLK_DISABLE +#define __ETHMACTX_CLK_ENABLE __HAL_RCC_ETHMACTX_CLK_ENABLE +#define __FIREWALL_CLK_DISABLE __HAL_RCC_FIREWALL_CLK_DISABLE +#define __FIREWALL_CLK_ENABLE __HAL_RCC_FIREWALL_CLK_ENABLE +#define __FLASH_CLK_DISABLE __HAL_RCC_FLASH_CLK_DISABLE +#define __FLASH_CLK_ENABLE __HAL_RCC_FLASH_CLK_ENABLE +#define __FLASH_CLK_SLEEP_DISABLE __HAL_RCC_FLASH_CLK_SLEEP_DISABLE +#define __FLASH_CLK_SLEEP_ENABLE __HAL_RCC_FLASH_CLK_SLEEP_ENABLE +#define __FLASH_FORCE_RESET __HAL_RCC_FLASH_FORCE_RESET +#define __FLASH_RELEASE_RESET __HAL_RCC_FLASH_RELEASE_RESET +#define __FLITF_CLK_DISABLE __HAL_RCC_FLITF_CLK_DISABLE +#define __FLITF_CLK_ENABLE __HAL_RCC_FLITF_CLK_ENABLE +#define __FLITF_FORCE_RESET __HAL_RCC_FLITF_FORCE_RESET +#define __FLITF_RELEASE_RESET __HAL_RCC_FLITF_RELEASE_RESET +#define __FLITF_CLK_SLEEP_ENABLE __HAL_RCC_FLITF_CLK_SLEEP_ENABLE +#define __FLITF_CLK_SLEEP_DISABLE __HAL_RCC_FLITF_CLK_SLEEP_DISABLE +#define __FMC_CLK_DISABLE __HAL_RCC_FMC_CLK_DISABLE +#define __FMC_CLK_ENABLE __HAL_RCC_FMC_CLK_ENABLE +#define __FMC_CLK_SLEEP_DISABLE __HAL_RCC_FMC_CLK_SLEEP_DISABLE +#define __FMC_CLK_SLEEP_ENABLE __HAL_RCC_FMC_CLK_SLEEP_ENABLE +#define __FMC_FORCE_RESET __HAL_RCC_FMC_FORCE_RESET +#define __FMC_RELEASE_RESET __HAL_RCC_FMC_RELEASE_RESET +#define __FSMC_CLK_DISABLE __HAL_RCC_FSMC_CLK_DISABLE +#define __FSMC_CLK_ENABLE __HAL_RCC_FSMC_CLK_ENABLE +#define __GPIOA_CLK_DISABLE __HAL_RCC_GPIOA_CLK_DISABLE +#define __GPIOA_CLK_ENABLE __HAL_RCC_GPIOA_CLK_ENABLE +#define __GPIOA_CLK_SLEEP_DISABLE __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE +#define __GPIOA_CLK_SLEEP_ENABLE __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE +#define __GPIOA_FORCE_RESET __HAL_RCC_GPIOA_FORCE_RESET +#define __GPIOA_RELEASE_RESET __HAL_RCC_GPIOA_RELEASE_RESET +#define __GPIOB_CLK_DISABLE __HAL_RCC_GPIOB_CLK_DISABLE +#define __GPIOB_CLK_ENABLE __HAL_RCC_GPIOB_CLK_ENABLE +#define __GPIOB_CLK_SLEEP_DISABLE __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE +#define __GPIOB_CLK_SLEEP_ENABLE __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE +#define __GPIOB_FORCE_RESET __HAL_RCC_GPIOB_FORCE_RESET +#define __GPIOB_RELEASE_RESET __HAL_RCC_GPIOB_RELEASE_RESET +#define __GPIOC_CLK_DISABLE __HAL_RCC_GPIOC_CLK_DISABLE +#define __GPIOC_CLK_ENABLE __HAL_RCC_GPIOC_CLK_ENABLE +#define __GPIOC_CLK_SLEEP_DISABLE __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE +#define __GPIOC_CLK_SLEEP_ENABLE __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE +#define __GPIOC_FORCE_RESET __HAL_RCC_GPIOC_FORCE_RESET +#define __GPIOC_RELEASE_RESET __HAL_RCC_GPIOC_RELEASE_RESET +#define __GPIOD_CLK_DISABLE __HAL_RCC_GPIOD_CLK_DISABLE +#define __GPIOD_CLK_ENABLE __HAL_RCC_GPIOD_CLK_ENABLE +#define __GPIOD_CLK_SLEEP_DISABLE __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE +#define __GPIOD_CLK_SLEEP_ENABLE __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE +#define __GPIOD_FORCE_RESET __HAL_RCC_GPIOD_FORCE_RESET +#define __GPIOD_RELEASE_RESET __HAL_RCC_GPIOD_RELEASE_RESET +#define __GPIOE_CLK_DISABLE __HAL_RCC_GPIOE_CLK_DISABLE +#define __GPIOE_CLK_ENABLE __HAL_RCC_GPIOE_CLK_ENABLE +#define __GPIOE_CLK_SLEEP_DISABLE __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE +#define __GPIOE_CLK_SLEEP_ENABLE __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE +#define __GPIOE_FORCE_RESET __HAL_RCC_GPIOE_FORCE_RESET +#define __GPIOE_RELEASE_RESET __HAL_RCC_GPIOE_RELEASE_RESET +#define __GPIOF_CLK_DISABLE __HAL_RCC_GPIOF_CLK_DISABLE +#define __GPIOF_CLK_ENABLE __HAL_RCC_GPIOF_CLK_ENABLE +#define __GPIOF_CLK_SLEEP_DISABLE __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE +#define __GPIOF_CLK_SLEEP_ENABLE __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE +#define __GPIOF_FORCE_RESET __HAL_RCC_GPIOF_FORCE_RESET +#define __GPIOF_RELEASE_RESET __HAL_RCC_GPIOF_RELEASE_RESET +#define __GPIOG_CLK_DISABLE __HAL_RCC_GPIOG_CLK_DISABLE +#define __GPIOG_CLK_ENABLE __HAL_RCC_GPIOG_CLK_ENABLE +#define __GPIOG_CLK_SLEEP_DISABLE __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE +#define __GPIOG_CLK_SLEEP_ENABLE __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE +#define __GPIOG_FORCE_RESET __HAL_RCC_GPIOG_FORCE_RESET +#define __GPIOG_RELEASE_RESET __HAL_RCC_GPIOG_RELEASE_RESET +#define __GPIOH_CLK_DISABLE __HAL_RCC_GPIOH_CLK_DISABLE +#define __GPIOH_CLK_ENABLE __HAL_RCC_GPIOH_CLK_ENABLE +#define __GPIOH_CLK_SLEEP_DISABLE __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE +#define __GPIOH_CLK_SLEEP_ENABLE __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE +#define __GPIOH_FORCE_RESET __HAL_RCC_GPIOH_FORCE_RESET +#define __GPIOH_RELEASE_RESET __HAL_RCC_GPIOH_RELEASE_RESET +#define __I2C1_CLK_DISABLE __HAL_RCC_I2C1_CLK_DISABLE +#define __I2C1_CLK_ENABLE __HAL_RCC_I2C1_CLK_ENABLE +#define __I2C1_CLK_SLEEP_DISABLE __HAL_RCC_I2C1_CLK_SLEEP_DISABLE +#define __I2C1_CLK_SLEEP_ENABLE __HAL_RCC_I2C1_CLK_SLEEP_ENABLE +#define __I2C1_FORCE_RESET __HAL_RCC_I2C1_FORCE_RESET +#define __I2C1_RELEASE_RESET __HAL_RCC_I2C1_RELEASE_RESET +#define __I2C2_CLK_DISABLE __HAL_RCC_I2C2_CLK_DISABLE +#define __I2C2_CLK_ENABLE __HAL_RCC_I2C2_CLK_ENABLE +#define __I2C2_CLK_SLEEP_DISABLE __HAL_RCC_I2C2_CLK_SLEEP_DISABLE +#define __I2C2_CLK_SLEEP_ENABLE __HAL_RCC_I2C2_CLK_SLEEP_ENABLE +#define __I2C2_FORCE_RESET __HAL_RCC_I2C2_FORCE_RESET +#define __I2C2_RELEASE_RESET __HAL_RCC_I2C2_RELEASE_RESET +#define __I2C3_CLK_DISABLE __HAL_RCC_I2C3_CLK_DISABLE +#define __I2C3_CLK_ENABLE __HAL_RCC_I2C3_CLK_ENABLE +#define __I2C3_CLK_SLEEP_DISABLE __HAL_RCC_I2C3_CLK_SLEEP_DISABLE +#define __I2C3_CLK_SLEEP_ENABLE __HAL_RCC_I2C3_CLK_SLEEP_ENABLE +#define __I2C3_FORCE_RESET __HAL_RCC_I2C3_FORCE_RESET +#define __I2C3_RELEASE_RESET __HAL_RCC_I2C3_RELEASE_RESET +#define __LCD_CLK_DISABLE __HAL_RCC_LCD_CLK_DISABLE +#define __LCD_CLK_ENABLE __HAL_RCC_LCD_CLK_ENABLE +#define __LCD_CLK_SLEEP_DISABLE __HAL_RCC_LCD_CLK_SLEEP_DISABLE +#define __LCD_CLK_SLEEP_ENABLE __HAL_RCC_LCD_CLK_SLEEP_ENABLE +#define __LCD_FORCE_RESET __HAL_RCC_LCD_FORCE_RESET +#define __LCD_RELEASE_RESET __HAL_RCC_LCD_RELEASE_RESET +#define __LPTIM1_CLK_DISABLE __HAL_RCC_LPTIM1_CLK_DISABLE +#define __LPTIM1_CLK_ENABLE __HAL_RCC_LPTIM1_CLK_ENABLE +#define __LPTIM1_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE +#define __LPTIM1_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE +#define __LPTIM1_FORCE_RESET __HAL_RCC_LPTIM1_FORCE_RESET +#define __LPTIM1_RELEASE_RESET __HAL_RCC_LPTIM1_RELEASE_RESET +#define __LPTIM2_CLK_DISABLE __HAL_RCC_LPTIM2_CLK_DISABLE +#define __LPTIM2_CLK_ENABLE __HAL_RCC_LPTIM2_CLK_ENABLE +#define __LPTIM2_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM2_CLK_SLEEP_DISABLE +#define __LPTIM2_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM2_CLK_SLEEP_ENABLE +#define __LPTIM2_FORCE_RESET __HAL_RCC_LPTIM2_FORCE_RESET +#define __LPTIM2_RELEASE_RESET __HAL_RCC_LPTIM2_RELEASE_RESET +#define __LPUART1_CLK_DISABLE __HAL_RCC_LPUART1_CLK_DISABLE +#define __LPUART1_CLK_ENABLE __HAL_RCC_LPUART1_CLK_ENABLE +#define __LPUART1_CLK_SLEEP_DISABLE __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE +#define __LPUART1_CLK_SLEEP_ENABLE __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE +#define __LPUART1_FORCE_RESET __HAL_RCC_LPUART1_FORCE_RESET +#define __LPUART1_RELEASE_RESET __HAL_RCC_LPUART1_RELEASE_RESET +#define __OPAMP_CLK_DISABLE __HAL_RCC_OPAMP_CLK_DISABLE +#define __OPAMP_CLK_ENABLE __HAL_RCC_OPAMP_CLK_ENABLE +#define __OPAMP_CLK_SLEEP_DISABLE __HAL_RCC_OPAMP_CLK_SLEEP_DISABLE +#define __OPAMP_CLK_SLEEP_ENABLE __HAL_RCC_OPAMP_CLK_SLEEP_ENABLE +#define __OPAMP_FORCE_RESET __HAL_RCC_OPAMP_FORCE_RESET +#define __OPAMP_RELEASE_RESET __HAL_RCC_OPAMP_RELEASE_RESET +#define __OTGFS_CLK_DISABLE __HAL_RCC_OTGFS_CLK_DISABLE +#define __OTGFS_CLK_ENABLE __HAL_RCC_OTGFS_CLK_ENABLE +#define __OTGFS_CLK_SLEEP_DISABLE __HAL_RCC_OTGFS_CLK_SLEEP_DISABLE +#define __OTGFS_CLK_SLEEP_ENABLE __HAL_RCC_OTGFS_CLK_SLEEP_ENABLE +#define __OTGFS_FORCE_RESET __HAL_RCC_OTGFS_FORCE_RESET +#define __OTGFS_RELEASE_RESET __HAL_RCC_OTGFS_RELEASE_RESET +#define __PWR_CLK_DISABLE __HAL_RCC_PWR_CLK_DISABLE +#define __PWR_CLK_ENABLE __HAL_RCC_PWR_CLK_ENABLE +#define __PWR_CLK_SLEEP_DISABLE __HAL_RCC_PWR_CLK_SLEEP_DISABLE +#define __PWR_CLK_SLEEP_ENABLE __HAL_RCC_PWR_CLK_SLEEP_ENABLE +#define __PWR_FORCE_RESET __HAL_RCC_PWR_FORCE_RESET +#define __PWR_RELEASE_RESET __HAL_RCC_PWR_RELEASE_RESET +#define __QSPI_CLK_DISABLE __HAL_RCC_QSPI_CLK_DISABLE +#define __QSPI_CLK_ENABLE __HAL_RCC_QSPI_CLK_ENABLE +#define __QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QSPI_CLK_SLEEP_DISABLE +#define __QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QSPI_CLK_SLEEP_ENABLE +#define __QSPI_FORCE_RESET __HAL_RCC_QSPI_FORCE_RESET +#define __QSPI_RELEASE_RESET __HAL_RCC_QSPI_RELEASE_RESET + +#if defined(STM32WB) +#define __HAL_RCC_QSPI_CLK_DISABLE __HAL_RCC_QUADSPI_CLK_DISABLE +#define __HAL_RCC_QSPI_CLK_ENABLE __HAL_RCC_QUADSPI_CLK_ENABLE +#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QUADSPI_CLK_SLEEP_DISABLE +#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QUADSPI_CLK_SLEEP_ENABLE +#define __HAL_RCC_QSPI_FORCE_RESET __HAL_RCC_QUADSPI_FORCE_RESET +#define __HAL_RCC_QSPI_RELEASE_RESET __HAL_RCC_QUADSPI_RELEASE_RESET +#define __HAL_RCC_QSPI_IS_CLK_ENABLED __HAL_RCC_QUADSPI_IS_CLK_ENABLED +#define __HAL_RCC_QSPI_IS_CLK_DISABLED __HAL_RCC_QUADSPI_IS_CLK_DISABLED +#define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_ENABLED +#define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_DISABLED +#define QSPI_IRQHandler QUADSPI_IRQHandler +#endif /* __HAL_RCC_QUADSPI_CLK_ENABLE */ + +#define __RNG_CLK_DISABLE __HAL_RCC_RNG_CLK_DISABLE +#define __RNG_CLK_ENABLE __HAL_RCC_RNG_CLK_ENABLE +#define __RNG_CLK_SLEEP_DISABLE __HAL_RCC_RNG_CLK_SLEEP_DISABLE +#define __RNG_CLK_SLEEP_ENABLE __HAL_RCC_RNG_CLK_SLEEP_ENABLE +#define __RNG_FORCE_RESET __HAL_RCC_RNG_FORCE_RESET +#define __RNG_RELEASE_RESET __HAL_RCC_RNG_RELEASE_RESET +#define __SAI1_CLK_DISABLE __HAL_RCC_SAI1_CLK_DISABLE +#define __SAI1_CLK_ENABLE __HAL_RCC_SAI1_CLK_ENABLE +#define __SAI1_CLK_SLEEP_DISABLE __HAL_RCC_SAI1_CLK_SLEEP_DISABLE +#define __SAI1_CLK_SLEEP_ENABLE __HAL_RCC_SAI1_CLK_SLEEP_ENABLE +#define __SAI1_FORCE_RESET __HAL_RCC_SAI1_FORCE_RESET +#define __SAI1_RELEASE_RESET __HAL_RCC_SAI1_RELEASE_RESET +#define __SAI2_CLK_DISABLE __HAL_RCC_SAI2_CLK_DISABLE +#define __SAI2_CLK_ENABLE __HAL_RCC_SAI2_CLK_ENABLE +#define __SAI2_CLK_SLEEP_DISABLE __HAL_RCC_SAI2_CLK_SLEEP_DISABLE +#define __SAI2_CLK_SLEEP_ENABLE __HAL_RCC_SAI2_CLK_SLEEP_ENABLE +#define __SAI2_FORCE_RESET __HAL_RCC_SAI2_FORCE_RESET +#define __SAI2_RELEASE_RESET __HAL_RCC_SAI2_RELEASE_RESET +#define __SDIO_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE +#define __SDIO_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE +#define __SDMMC_CLK_DISABLE __HAL_RCC_SDMMC_CLK_DISABLE +#define __SDMMC_CLK_ENABLE __HAL_RCC_SDMMC_CLK_ENABLE +#define __SDMMC_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC_CLK_SLEEP_DISABLE +#define __SDMMC_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC_CLK_SLEEP_ENABLE +#define __SDMMC_FORCE_RESET __HAL_RCC_SDMMC_FORCE_RESET +#define __SDMMC_RELEASE_RESET __HAL_RCC_SDMMC_RELEASE_RESET +#define __SPI1_CLK_DISABLE __HAL_RCC_SPI1_CLK_DISABLE +#define __SPI1_CLK_ENABLE __HAL_RCC_SPI1_CLK_ENABLE +#define __SPI1_CLK_SLEEP_DISABLE __HAL_RCC_SPI1_CLK_SLEEP_DISABLE +#define __SPI1_CLK_SLEEP_ENABLE __HAL_RCC_SPI1_CLK_SLEEP_ENABLE +#define __SPI1_FORCE_RESET __HAL_RCC_SPI1_FORCE_RESET +#define __SPI1_RELEASE_RESET __HAL_RCC_SPI1_RELEASE_RESET +#define __SPI2_CLK_DISABLE __HAL_RCC_SPI2_CLK_DISABLE +#define __SPI2_CLK_ENABLE __HAL_RCC_SPI2_CLK_ENABLE +#define __SPI2_CLK_SLEEP_DISABLE __HAL_RCC_SPI2_CLK_SLEEP_DISABLE +#define __SPI2_CLK_SLEEP_ENABLE __HAL_RCC_SPI2_CLK_SLEEP_ENABLE +#define __SPI2_FORCE_RESET __HAL_RCC_SPI2_FORCE_RESET +#define __SPI2_RELEASE_RESET __HAL_RCC_SPI2_RELEASE_RESET +#define __SPI3_CLK_DISABLE __HAL_RCC_SPI3_CLK_DISABLE +#define __SPI3_CLK_ENABLE __HAL_RCC_SPI3_CLK_ENABLE +#define __SPI3_CLK_SLEEP_DISABLE __HAL_RCC_SPI3_CLK_SLEEP_DISABLE +#define __SPI3_CLK_SLEEP_ENABLE __HAL_RCC_SPI3_CLK_SLEEP_ENABLE +#define __SPI3_FORCE_RESET __HAL_RCC_SPI3_FORCE_RESET +#define __SPI3_RELEASE_RESET __HAL_RCC_SPI3_RELEASE_RESET +#define __SRAM_CLK_DISABLE __HAL_RCC_SRAM_CLK_DISABLE +#define __SRAM_CLK_ENABLE __HAL_RCC_SRAM_CLK_ENABLE +#define __SRAM1_CLK_SLEEP_DISABLE __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE +#define __SRAM1_CLK_SLEEP_ENABLE __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE +#define __SRAM2_CLK_SLEEP_DISABLE __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE +#define __SRAM2_CLK_SLEEP_ENABLE __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE +#define __SWPMI1_CLK_DISABLE __HAL_RCC_SWPMI1_CLK_DISABLE +#define __SWPMI1_CLK_ENABLE __HAL_RCC_SWPMI1_CLK_ENABLE +#define __SWPMI1_CLK_SLEEP_DISABLE __HAL_RCC_SWPMI1_CLK_SLEEP_DISABLE +#define __SWPMI1_CLK_SLEEP_ENABLE __HAL_RCC_SWPMI1_CLK_SLEEP_ENABLE +#define __SWPMI1_FORCE_RESET __HAL_RCC_SWPMI1_FORCE_RESET +#define __SWPMI1_RELEASE_RESET __HAL_RCC_SWPMI1_RELEASE_RESET +#define __SYSCFG_CLK_DISABLE __HAL_RCC_SYSCFG_CLK_DISABLE +#define __SYSCFG_CLK_ENABLE __HAL_RCC_SYSCFG_CLK_ENABLE +#define __SYSCFG_CLK_SLEEP_DISABLE __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE +#define __SYSCFG_CLK_SLEEP_ENABLE __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE +#define __SYSCFG_FORCE_RESET __HAL_RCC_SYSCFG_FORCE_RESET +#define __SYSCFG_RELEASE_RESET __HAL_RCC_SYSCFG_RELEASE_RESET +#define __TIM1_CLK_DISABLE __HAL_RCC_TIM1_CLK_DISABLE +#define __TIM1_CLK_ENABLE __HAL_RCC_TIM1_CLK_ENABLE +#define __TIM1_CLK_SLEEP_DISABLE __HAL_RCC_TIM1_CLK_SLEEP_DISABLE +#define __TIM1_CLK_SLEEP_ENABLE __HAL_RCC_TIM1_CLK_SLEEP_ENABLE +#define __TIM1_FORCE_RESET __HAL_RCC_TIM1_FORCE_RESET +#define __TIM1_RELEASE_RESET __HAL_RCC_TIM1_RELEASE_RESET +#define __TIM10_CLK_DISABLE __HAL_RCC_TIM10_CLK_DISABLE +#define __TIM10_CLK_ENABLE __HAL_RCC_TIM10_CLK_ENABLE +#define __TIM10_FORCE_RESET __HAL_RCC_TIM10_FORCE_RESET +#define __TIM10_RELEASE_RESET __HAL_RCC_TIM10_RELEASE_RESET +#define __TIM11_CLK_DISABLE __HAL_RCC_TIM11_CLK_DISABLE +#define __TIM11_CLK_ENABLE __HAL_RCC_TIM11_CLK_ENABLE +#define __TIM11_FORCE_RESET __HAL_RCC_TIM11_FORCE_RESET +#define __TIM11_RELEASE_RESET __HAL_RCC_TIM11_RELEASE_RESET +#define __TIM12_CLK_DISABLE __HAL_RCC_TIM12_CLK_DISABLE +#define __TIM12_CLK_ENABLE __HAL_RCC_TIM12_CLK_ENABLE +#define __TIM12_FORCE_RESET __HAL_RCC_TIM12_FORCE_RESET +#define __TIM12_RELEASE_RESET __HAL_RCC_TIM12_RELEASE_RESET +#define __TIM13_CLK_DISABLE __HAL_RCC_TIM13_CLK_DISABLE +#define __TIM13_CLK_ENABLE __HAL_RCC_TIM13_CLK_ENABLE +#define __TIM13_FORCE_RESET __HAL_RCC_TIM13_FORCE_RESET +#define __TIM13_RELEASE_RESET __HAL_RCC_TIM13_RELEASE_RESET +#define __TIM14_CLK_DISABLE __HAL_RCC_TIM14_CLK_DISABLE +#define __TIM14_CLK_ENABLE __HAL_RCC_TIM14_CLK_ENABLE +#define __TIM14_FORCE_RESET __HAL_RCC_TIM14_FORCE_RESET +#define __TIM14_RELEASE_RESET __HAL_RCC_TIM14_RELEASE_RESET +#define __TIM15_CLK_DISABLE __HAL_RCC_TIM15_CLK_DISABLE +#define __TIM15_CLK_ENABLE __HAL_RCC_TIM15_CLK_ENABLE +#define __TIM15_CLK_SLEEP_DISABLE __HAL_RCC_TIM15_CLK_SLEEP_DISABLE +#define __TIM15_CLK_SLEEP_ENABLE __HAL_RCC_TIM15_CLK_SLEEP_ENABLE +#define __TIM15_FORCE_RESET __HAL_RCC_TIM15_FORCE_RESET +#define __TIM15_RELEASE_RESET __HAL_RCC_TIM15_RELEASE_RESET +#define __TIM16_CLK_DISABLE __HAL_RCC_TIM16_CLK_DISABLE +#define __TIM16_CLK_ENABLE __HAL_RCC_TIM16_CLK_ENABLE +#define __TIM16_CLK_SLEEP_DISABLE __HAL_RCC_TIM16_CLK_SLEEP_DISABLE +#define __TIM16_CLK_SLEEP_ENABLE __HAL_RCC_TIM16_CLK_SLEEP_ENABLE +#define __TIM16_FORCE_RESET __HAL_RCC_TIM16_FORCE_RESET +#define __TIM16_RELEASE_RESET __HAL_RCC_TIM16_RELEASE_RESET +#define __TIM17_CLK_DISABLE __HAL_RCC_TIM17_CLK_DISABLE +#define __TIM17_CLK_ENABLE __HAL_RCC_TIM17_CLK_ENABLE +#define __TIM17_CLK_SLEEP_DISABLE __HAL_RCC_TIM17_CLK_SLEEP_DISABLE +#define __TIM17_CLK_SLEEP_ENABLE __HAL_RCC_TIM17_CLK_SLEEP_ENABLE +#define __TIM17_FORCE_RESET __HAL_RCC_TIM17_FORCE_RESET +#define __TIM17_RELEASE_RESET __HAL_RCC_TIM17_RELEASE_RESET +#define __TIM2_CLK_DISABLE __HAL_RCC_TIM2_CLK_DISABLE +#define __TIM2_CLK_ENABLE __HAL_RCC_TIM2_CLK_ENABLE +#define __TIM2_CLK_SLEEP_DISABLE __HAL_RCC_TIM2_CLK_SLEEP_DISABLE +#define __TIM2_CLK_SLEEP_ENABLE __HAL_RCC_TIM2_CLK_SLEEP_ENABLE +#define __TIM2_FORCE_RESET __HAL_RCC_TIM2_FORCE_RESET +#define __TIM2_RELEASE_RESET __HAL_RCC_TIM2_RELEASE_RESET +#define __TIM3_CLK_DISABLE __HAL_RCC_TIM3_CLK_DISABLE +#define __TIM3_CLK_ENABLE __HAL_RCC_TIM3_CLK_ENABLE +#define __TIM3_CLK_SLEEP_DISABLE __HAL_RCC_TIM3_CLK_SLEEP_DISABLE +#define __TIM3_CLK_SLEEP_ENABLE __HAL_RCC_TIM3_CLK_SLEEP_ENABLE +#define __TIM3_FORCE_RESET __HAL_RCC_TIM3_FORCE_RESET +#define __TIM3_RELEASE_RESET __HAL_RCC_TIM3_RELEASE_RESET +#define __TIM4_CLK_DISABLE __HAL_RCC_TIM4_CLK_DISABLE +#define __TIM4_CLK_ENABLE __HAL_RCC_TIM4_CLK_ENABLE +#define __TIM4_CLK_SLEEP_DISABLE __HAL_RCC_TIM4_CLK_SLEEP_DISABLE +#define __TIM4_CLK_SLEEP_ENABLE __HAL_RCC_TIM4_CLK_SLEEP_ENABLE +#define __TIM4_FORCE_RESET __HAL_RCC_TIM4_FORCE_RESET +#define __TIM4_RELEASE_RESET __HAL_RCC_TIM4_RELEASE_RESET +#define __TIM5_CLK_DISABLE __HAL_RCC_TIM5_CLK_DISABLE +#define __TIM5_CLK_ENABLE __HAL_RCC_TIM5_CLK_ENABLE +#define __TIM5_CLK_SLEEP_DISABLE __HAL_RCC_TIM5_CLK_SLEEP_DISABLE +#define __TIM5_CLK_SLEEP_ENABLE __HAL_RCC_TIM5_CLK_SLEEP_ENABLE +#define __TIM5_FORCE_RESET __HAL_RCC_TIM5_FORCE_RESET +#define __TIM5_RELEASE_RESET __HAL_RCC_TIM5_RELEASE_RESET +#define __TIM6_CLK_DISABLE __HAL_RCC_TIM6_CLK_DISABLE +#define __TIM6_CLK_ENABLE __HAL_RCC_TIM6_CLK_ENABLE +#define __TIM6_CLK_SLEEP_DISABLE __HAL_RCC_TIM6_CLK_SLEEP_DISABLE +#define __TIM6_CLK_SLEEP_ENABLE __HAL_RCC_TIM6_CLK_SLEEP_ENABLE +#define __TIM6_FORCE_RESET __HAL_RCC_TIM6_FORCE_RESET +#define __TIM6_RELEASE_RESET __HAL_RCC_TIM6_RELEASE_RESET +#define __TIM7_CLK_DISABLE __HAL_RCC_TIM7_CLK_DISABLE +#define __TIM7_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE +#define __TIM7_CLK_SLEEP_DISABLE __HAL_RCC_TIM7_CLK_SLEEP_DISABLE +#define __TIM7_CLK_SLEEP_ENABLE __HAL_RCC_TIM7_CLK_SLEEP_ENABLE +#define __TIM7_FORCE_RESET __HAL_RCC_TIM7_FORCE_RESET +#define __TIM7_RELEASE_RESET __HAL_RCC_TIM7_RELEASE_RESET +#define __TIM8_CLK_DISABLE __HAL_RCC_TIM8_CLK_DISABLE +#define __TIM8_CLK_ENABLE __HAL_RCC_TIM8_CLK_ENABLE +#define __TIM8_CLK_SLEEP_DISABLE __HAL_RCC_TIM8_CLK_SLEEP_DISABLE +#define __TIM8_CLK_SLEEP_ENABLE __HAL_RCC_TIM8_CLK_SLEEP_ENABLE +#define __TIM8_FORCE_RESET __HAL_RCC_TIM8_FORCE_RESET +#define __TIM8_RELEASE_RESET __HAL_RCC_TIM8_RELEASE_RESET +#define __TIM9_CLK_DISABLE __HAL_RCC_TIM9_CLK_DISABLE +#define __TIM9_CLK_ENABLE __HAL_RCC_TIM9_CLK_ENABLE +#define __TIM9_FORCE_RESET __HAL_RCC_TIM9_FORCE_RESET +#define __TIM9_RELEASE_RESET __HAL_RCC_TIM9_RELEASE_RESET +#define __TSC_CLK_DISABLE __HAL_RCC_TSC_CLK_DISABLE +#define __TSC_CLK_ENABLE __HAL_RCC_TSC_CLK_ENABLE +#define __TSC_CLK_SLEEP_DISABLE __HAL_RCC_TSC_CLK_SLEEP_DISABLE +#define __TSC_CLK_SLEEP_ENABLE __HAL_RCC_TSC_CLK_SLEEP_ENABLE +#define __TSC_FORCE_RESET __HAL_RCC_TSC_FORCE_RESET +#define __TSC_RELEASE_RESET __HAL_RCC_TSC_RELEASE_RESET +#define __UART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE +#define __UART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE +#define __UART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE +#define __UART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE +#define __UART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET +#define __UART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET +#define __UART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE +#define __UART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE +#define __UART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE +#define __UART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE +#define __UART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET +#define __UART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET +#define __USART1_CLK_DISABLE __HAL_RCC_USART1_CLK_DISABLE +#define __USART1_CLK_ENABLE __HAL_RCC_USART1_CLK_ENABLE +#define __USART1_CLK_SLEEP_DISABLE __HAL_RCC_USART1_CLK_SLEEP_DISABLE +#define __USART1_CLK_SLEEP_ENABLE __HAL_RCC_USART1_CLK_SLEEP_ENABLE +#define __USART1_FORCE_RESET __HAL_RCC_USART1_FORCE_RESET +#define __USART1_RELEASE_RESET __HAL_RCC_USART1_RELEASE_RESET +#define __USART2_CLK_DISABLE __HAL_RCC_USART2_CLK_DISABLE +#define __USART2_CLK_ENABLE __HAL_RCC_USART2_CLK_ENABLE +#define __USART2_CLK_SLEEP_DISABLE __HAL_RCC_USART2_CLK_SLEEP_DISABLE +#define __USART2_CLK_SLEEP_ENABLE __HAL_RCC_USART2_CLK_SLEEP_ENABLE +#define __USART2_FORCE_RESET __HAL_RCC_USART2_FORCE_RESET +#define __USART2_RELEASE_RESET __HAL_RCC_USART2_RELEASE_RESET +#define __USART3_CLK_DISABLE __HAL_RCC_USART3_CLK_DISABLE +#define __USART3_CLK_ENABLE __HAL_RCC_USART3_CLK_ENABLE +#define __USART3_CLK_SLEEP_DISABLE __HAL_RCC_USART3_CLK_SLEEP_DISABLE +#define __USART3_CLK_SLEEP_ENABLE __HAL_RCC_USART3_CLK_SLEEP_ENABLE +#define __USART3_FORCE_RESET __HAL_RCC_USART3_FORCE_RESET +#define __USART3_RELEASE_RESET __HAL_RCC_USART3_RELEASE_RESET +#define __USART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE +#define __USART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE +#define __USART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE +#define __USART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE +#define __USART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET +#define __USART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET +#define __USART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE +#define __USART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE +#define __USART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE +#define __USART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE +#define __USART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET +#define __USART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET +#define __USART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE +#define __USART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE +#define __USART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET +#define __USART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET +#define __USART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE +#define __USART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE +#define __USART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET +#define __USART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET +#define __USB_CLK_DISABLE __HAL_RCC_USB_CLK_DISABLE +#define __USB_CLK_ENABLE __HAL_RCC_USB_CLK_ENABLE +#define __USB_FORCE_RESET __HAL_RCC_USB_FORCE_RESET +#define __USB_CLK_SLEEP_ENABLE __HAL_RCC_USB_CLK_SLEEP_ENABLE +#define __USB_CLK_SLEEP_DISABLE __HAL_RCC_USB_CLK_SLEEP_DISABLE +#define __USB_OTG_FS_CLK_DISABLE __HAL_RCC_USB_OTG_FS_CLK_DISABLE +#define __USB_OTG_FS_CLK_ENABLE __HAL_RCC_USB_OTG_FS_CLK_ENABLE +#define __USB_RELEASE_RESET __HAL_RCC_USB_RELEASE_RESET + +#if defined(STM32H7) +#define __HAL_RCC_WWDG_CLK_DISABLE __HAL_RCC_WWDG1_CLK_DISABLE +#define __HAL_RCC_WWDG_CLK_ENABLE __HAL_RCC_WWDG1_CLK_ENABLE +#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG1_CLK_SLEEP_DISABLE +#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG1_CLK_SLEEP_ENABLE + +#define __HAL_RCC_WWDG_FORCE_RESET ((void)0U) /* Not available on the STM32H7*/ +#define __HAL_RCC_WWDG_RELEASE_RESET ((void)0U) /* Not available on the STM32H7*/ + + +#define __HAL_RCC_WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG1_IS_CLK_ENABLED +#define __HAL_RCC_WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG1_IS_CLK_DISABLED +#endif + +#define __WWDG_CLK_DISABLE __HAL_RCC_WWDG_CLK_DISABLE +#define __WWDG_CLK_ENABLE __HAL_RCC_WWDG_CLK_ENABLE +#define __WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG_CLK_SLEEP_DISABLE +#define __WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG_CLK_SLEEP_ENABLE +#define __WWDG_FORCE_RESET __HAL_RCC_WWDG_FORCE_RESET +#define __WWDG_RELEASE_RESET __HAL_RCC_WWDG_RELEASE_RESET + +#define __TIM21_CLK_ENABLE __HAL_RCC_TIM21_CLK_ENABLE +#define __TIM21_CLK_DISABLE __HAL_RCC_TIM21_CLK_DISABLE +#define __TIM21_FORCE_RESET __HAL_RCC_TIM21_FORCE_RESET +#define __TIM21_RELEASE_RESET __HAL_RCC_TIM21_RELEASE_RESET +#define __TIM21_CLK_SLEEP_ENABLE __HAL_RCC_TIM21_CLK_SLEEP_ENABLE +#define __TIM21_CLK_SLEEP_DISABLE __HAL_RCC_TIM21_CLK_SLEEP_DISABLE +#define __TIM22_CLK_ENABLE __HAL_RCC_TIM22_CLK_ENABLE +#define __TIM22_CLK_DISABLE __HAL_RCC_TIM22_CLK_DISABLE +#define __TIM22_FORCE_RESET __HAL_RCC_TIM22_FORCE_RESET +#define __TIM22_RELEASE_RESET __HAL_RCC_TIM22_RELEASE_RESET +#define __TIM22_CLK_SLEEP_ENABLE __HAL_RCC_TIM22_CLK_SLEEP_ENABLE +#define __TIM22_CLK_SLEEP_DISABLE __HAL_RCC_TIM22_CLK_SLEEP_DISABLE +#define __CRS_CLK_DISABLE __HAL_RCC_CRS_CLK_DISABLE +#define __CRS_CLK_ENABLE __HAL_RCC_CRS_CLK_ENABLE +#define __CRS_CLK_SLEEP_DISABLE __HAL_RCC_CRS_CLK_SLEEP_DISABLE +#define __CRS_CLK_SLEEP_ENABLE __HAL_RCC_CRS_CLK_SLEEP_ENABLE +#define __CRS_FORCE_RESET __HAL_RCC_CRS_FORCE_RESET +#define __CRS_RELEASE_RESET __HAL_RCC_CRS_RELEASE_RESET +#define __RCC_BACKUPRESET_FORCE __HAL_RCC_BACKUPRESET_FORCE +#define __RCC_BACKUPRESET_RELEASE __HAL_RCC_BACKUPRESET_RELEASE + +#define __USB_OTG_FS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET +#define __USB_OTG_FS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET +#define __USB_OTG_FS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE +#define __USB_OTG_FS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE +#define __USB_OTG_HS_CLK_DISABLE __HAL_RCC_USB_OTG_HS_CLK_DISABLE +#define __USB_OTG_HS_CLK_ENABLE __HAL_RCC_USB_OTG_HS_CLK_ENABLE +#define __USB_OTG_HS_ULPI_CLK_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE +#define __USB_OTG_HS_ULPI_CLK_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE +#define __TIM9_CLK_SLEEP_ENABLE __HAL_RCC_TIM9_CLK_SLEEP_ENABLE +#define __TIM9_CLK_SLEEP_DISABLE __HAL_RCC_TIM9_CLK_SLEEP_DISABLE +#define __TIM10_CLK_SLEEP_ENABLE __HAL_RCC_TIM10_CLK_SLEEP_ENABLE +#define __TIM10_CLK_SLEEP_DISABLE __HAL_RCC_TIM10_CLK_SLEEP_DISABLE +#define __TIM11_CLK_SLEEP_ENABLE __HAL_RCC_TIM11_CLK_SLEEP_ENABLE +#define __TIM11_CLK_SLEEP_DISABLE __HAL_RCC_TIM11_CLK_SLEEP_DISABLE +#define __ETHMACPTP_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE +#define __ETHMACPTP_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE +#define __ETHMACPTP_CLK_ENABLE __HAL_RCC_ETHMACPTP_CLK_ENABLE +#define __ETHMACPTP_CLK_DISABLE __HAL_RCC_ETHMACPTP_CLK_DISABLE +#define __HASH_CLK_ENABLE __HAL_RCC_HASH_CLK_ENABLE +#define __HASH_FORCE_RESET __HAL_RCC_HASH_FORCE_RESET +#define __HASH_RELEASE_RESET __HAL_RCC_HASH_RELEASE_RESET +#define __HASH_CLK_SLEEP_ENABLE __HAL_RCC_HASH_CLK_SLEEP_ENABLE +#define __HASH_CLK_SLEEP_DISABLE __HAL_RCC_HASH_CLK_SLEEP_DISABLE +#define __HASH_CLK_DISABLE __HAL_RCC_HASH_CLK_DISABLE +#define __SPI5_CLK_ENABLE __HAL_RCC_SPI5_CLK_ENABLE +#define __SPI5_CLK_DISABLE __HAL_RCC_SPI5_CLK_DISABLE +#define __SPI5_FORCE_RESET __HAL_RCC_SPI5_FORCE_RESET +#define __SPI5_RELEASE_RESET __HAL_RCC_SPI5_RELEASE_RESET +#define __SPI5_CLK_SLEEP_ENABLE __HAL_RCC_SPI5_CLK_SLEEP_ENABLE +#define __SPI5_CLK_SLEEP_DISABLE __HAL_RCC_SPI5_CLK_SLEEP_DISABLE +#define __SPI6_CLK_ENABLE __HAL_RCC_SPI6_CLK_ENABLE +#define __SPI6_CLK_DISABLE __HAL_RCC_SPI6_CLK_DISABLE +#define __SPI6_FORCE_RESET __HAL_RCC_SPI6_FORCE_RESET +#define __SPI6_RELEASE_RESET __HAL_RCC_SPI6_RELEASE_RESET +#define __SPI6_CLK_SLEEP_ENABLE __HAL_RCC_SPI6_CLK_SLEEP_ENABLE +#define __SPI6_CLK_SLEEP_DISABLE __HAL_RCC_SPI6_CLK_SLEEP_DISABLE +#define __LTDC_CLK_ENABLE __HAL_RCC_LTDC_CLK_ENABLE +#define __LTDC_CLK_DISABLE __HAL_RCC_LTDC_CLK_DISABLE +#define __LTDC_FORCE_RESET __HAL_RCC_LTDC_FORCE_RESET +#define __LTDC_RELEASE_RESET __HAL_RCC_LTDC_RELEASE_RESET +#define __LTDC_CLK_SLEEP_ENABLE __HAL_RCC_LTDC_CLK_SLEEP_ENABLE +#define __ETHMAC_CLK_SLEEP_ENABLE __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE +#define __ETHMAC_CLK_SLEEP_DISABLE __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE +#define __ETHMACTX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE +#define __ETHMACTX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE +#define __ETHMACRX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE +#define __ETHMACRX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE +#define __TIM12_CLK_SLEEP_ENABLE __HAL_RCC_TIM12_CLK_SLEEP_ENABLE +#define __TIM12_CLK_SLEEP_DISABLE __HAL_RCC_TIM12_CLK_SLEEP_DISABLE +#define __TIM13_CLK_SLEEP_ENABLE __HAL_RCC_TIM13_CLK_SLEEP_ENABLE +#define __TIM13_CLK_SLEEP_DISABLE __HAL_RCC_TIM13_CLK_SLEEP_DISABLE +#define __TIM14_CLK_SLEEP_ENABLE __HAL_RCC_TIM14_CLK_SLEEP_ENABLE +#define __TIM14_CLK_SLEEP_DISABLE __HAL_RCC_TIM14_CLK_SLEEP_DISABLE +#define __BKPSRAM_CLK_ENABLE __HAL_RCC_BKPSRAM_CLK_ENABLE +#define __BKPSRAM_CLK_DISABLE __HAL_RCC_BKPSRAM_CLK_DISABLE +#define __BKPSRAM_CLK_SLEEP_ENABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE +#define __BKPSRAM_CLK_SLEEP_DISABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE +#define __CCMDATARAMEN_CLK_ENABLE __HAL_RCC_CCMDATARAMEN_CLK_ENABLE +#define __CCMDATARAMEN_CLK_DISABLE __HAL_RCC_CCMDATARAMEN_CLK_DISABLE +#define __USART6_CLK_ENABLE __HAL_RCC_USART6_CLK_ENABLE +#define __USART6_CLK_DISABLE __HAL_RCC_USART6_CLK_DISABLE +#define __USART6_FORCE_RESET __HAL_RCC_USART6_FORCE_RESET +#define __USART6_RELEASE_RESET __HAL_RCC_USART6_RELEASE_RESET +#define __USART6_CLK_SLEEP_ENABLE __HAL_RCC_USART6_CLK_SLEEP_ENABLE +#define __USART6_CLK_SLEEP_DISABLE __HAL_RCC_USART6_CLK_SLEEP_DISABLE +#define __SPI4_CLK_ENABLE __HAL_RCC_SPI4_CLK_ENABLE +#define __SPI4_CLK_DISABLE __HAL_RCC_SPI4_CLK_DISABLE +#define __SPI4_FORCE_RESET __HAL_RCC_SPI4_FORCE_RESET +#define __SPI4_RELEASE_RESET __HAL_RCC_SPI4_RELEASE_RESET +#define __SPI4_CLK_SLEEP_ENABLE __HAL_RCC_SPI4_CLK_SLEEP_ENABLE +#define __SPI4_CLK_SLEEP_DISABLE __HAL_RCC_SPI4_CLK_SLEEP_DISABLE +#define __GPIOI_CLK_ENABLE __HAL_RCC_GPIOI_CLK_ENABLE +#define __GPIOI_CLK_DISABLE __HAL_RCC_GPIOI_CLK_DISABLE +#define __GPIOI_FORCE_RESET __HAL_RCC_GPIOI_FORCE_RESET +#define __GPIOI_RELEASE_RESET __HAL_RCC_GPIOI_RELEASE_RESET +#define __GPIOI_CLK_SLEEP_ENABLE __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE +#define __GPIOI_CLK_SLEEP_DISABLE __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE +#define __GPIOJ_CLK_ENABLE __HAL_RCC_GPIOJ_CLK_ENABLE +#define __GPIOJ_CLK_DISABLE __HAL_RCC_GPIOJ_CLK_DISABLE +#define __GPIOJ_FORCE_RESET __HAL_RCC_GPIOJ_FORCE_RESET +#define __GPIOJ_RELEASE_RESET __HAL_RCC_GPIOJ_RELEASE_RESET +#define __GPIOJ_CLK_SLEEP_ENABLE __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE +#define __GPIOJ_CLK_SLEEP_DISABLE __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE +#define __GPIOK_CLK_ENABLE __HAL_RCC_GPIOK_CLK_ENABLE +#define __GPIOK_CLK_DISABLE __HAL_RCC_GPIOK_CLK_DISABLE +#define __GPIOK_RELEASE_RESET __HAL_RCC_GPIOK_RELEASE_RESET +#define __GPIOK_CLK_SLEEP_ENABLE __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE +#define __GPIOK_CLK_SLEEP_DISABLE __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE +#define __ETH_CLK_ENABLE __HAL_RCC_ETH_CLK_ENABLE +#define __ETH_CLK_DISABLE __HAL_RCC_ETH_CLK_DISABLE +#define __DCMI_CLK_ENABLE __HAL_RCC_DCMI_CLK_ENABLE +#define __DCMI_CLK_DISABLE __HAL_RCC_DCMI_CLK_DISABLE +#define __DCMI_FORCE_RESET __HAL_RCC_DCMI_FORCE_RESET +#define __DCMI_RELEASE_RESET __HAL_RCC_DCMI_RELEASE_RESET +#define __DCMI_CLK_SLEEP_ENABLE __HAL_RCC_DCMI_CLK_SLEEP_ENABLE +#define __DCMI_CLK_SLEEP_DISABLE __HAL_RCC_DCMI_CLK_SLEEP_DISABLE +#define __UART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE +#define __UART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE +#define __UART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET +#define __UART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET +#define __UART7_CLK_SLEEP_ENABLE __HAL_RCC_UART7_CLK_SLEEP_ENABLE +#define __UART7_CLK_SLEEP_DISABLE __HAL_RCC_UART7_CLK_SLEEP_DISABLE +#define __UART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE +#define __UART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE +#define __UART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET +#define __UART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET +#define __UART8_CLK_SLEEP_ENABLE __HAL_RCC_UART8_CLK_SLEEP_ENABLE +#define __UART8_CLK_SLEEP_DISABLE __HAL_RCC_UART8_CLK_SLEEP_DISABLE +#define __OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE +#define __OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE +#define __OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET +#define __OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET +#define __OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE +#define __OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE +#define __HAL_RCC_OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE +#define __HAL_RCC_OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE +#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_ENABLED +#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_DISABLED +#define __HAL_RCC_OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET +#define __HAL_RCC_OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET +#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE +#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE +#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_ENABLED +#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_DISABLED +#define __SRAM3_CLK_SLEEP_ENABLE __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE +#define __CAN2_CLK_SLEEP_ENABLE __HAL_RCC_CAN2_CLK_SLEEP_ENABLE +#define __CAN2_CLK_SLEEP_DISABLE __HAL_RCC_CAN2_CLK_SLEEP_DISABLE +#define __DAC_CLK_SLEEP_ENABLE __HAL_RCC_DAC_CLK_SLEEP_ENABLE +#define __DAC_CLK_SLEEP_DISABLE __HAL_RCC_DAC_CLK_SLEEP_DISABLE +#define __ADC2_CLK_SLEEP_ENABLE __HAL_RCC_ADC2_CLK_SLEEP_ENABLE +#define __ADC2_CLK_SLEEP_DISABLE __HAL_RCC_ADC2_CLK_SLEEP_DISABLE +#define __ADC3_CLK_SLEEP_ENABLE __HAL_RCC_ADC3_CLK_SLEEP_ENABLE +#define __ADC3_CLK_SLEEP_DISABLE __HAL_RCC_ADC3_CLK_SLEEP_DISABLE +#define __FSMC_FORCE_RESET __HAL_RCC_FSMC_FORCE_RESET +#define __FSMC_RELEASE_RESET __HAL_RCC_FSMC_RELEASE_RESET +#define __FSMC_CLK_SLEEP_ENABLE __HAL_RCC_FSMC_CLK_SLEEP_ENABLE +#define __FSMC_CLK_SLEEP_DISABLE __HAL_RCC_FSMC_CLK_SLEEP_DISABLE +#define __SDIO_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET +#define __SDIO_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET +#define __SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE +#define __SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE +#define __DMA2D_CLK_ENABLE __HAL_RCC_DMA2D_CLK_ENABLE +#define __DMA2D_CLK_DISABLE __HAL_RCC_DMA2D_CLK_DISABLE +#define __DMA2D_FORCE_RESET __HAL_RCC_DMA2D_FORCE_RESET +#define __DMA2D_RELEASE_RESET __HAL_RCC_DMA2D_RELEASE_RESET +#define __DMA2D_CLK_SLEEP_ENABLE __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE +#define __DMA2D_CLK_SLEEP_DISABLE __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE + +/* alias define maintained for legacy */ +#define __HAL_RCC_OTGFS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET +#define __HAL_RCC_OTGFS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET + +#define __ADC12_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE +#define __ADC12_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE +#define __ADC34_CLK_ENABLE __HAL_RCC_ADC34_CLK_ENABLE +#define __ADC34_CLK_DISABLE __HAL_RCC_ADC34_CLK_DISABLE +#define __DAC2_CLK_ENABLE __HAL_RCC_DAC2_CLK_ENABLE +#define __DAC2_CLK_DISABLE __HAL_RCC_DAC2_CLK_DISABLE +#define __TIM18_CLK_ENABLE __HAL_RCC_TIM18_CLK_ENABLE +#define __TIM18_CLK_DISABLE __HAL_RCC_TIM18_CLK_DISABLE +#define __TIM19_CLK_ENABLE __HAL_RCC_TIM19_CLK_ENABLE +#define __TIM19_CLK_DISABLE __HAL_RCC_TIM19_CLK_DISABLE +#define __TIM20_CLK_ENABLE __HAL_RCC_TIM20_CLK_ENABLE +#define __TIM20_CLK_DISABLE __HAL_RCC_TIM20_CLK_DISABLE +#define __HRTIM1_CLK_ENABLE __HAL_RCC_HRTIM1_CLK_ENABLE +#define __HRTIM1_CLK_DISABLE __HAL_RCC_HRTIM1_CLK_DISABLE +#define __SDADC1_CLK_ENABLE __HAL_RCC_SDADC1_CLK_ENABLE +#define __SDADC2_CLK_ENABLE __HAL_RCC_SDADC2_CLK_ENABLE +#define __SDADC3_CLK_ENABLE __HAL_RCC_SDADC3_CLK_ENABLE +#define __SDADC1_CLK_DISABLE __HAL_RCC_SDADC1_CLK_DISABLE +#define __SDADC2_CLK_DISABLE __HAL_RCC_SDADC2_CLK_DISABLE +#define __SDADC3_CLK_DISABLE __HAL_RCC_SDADC3_CLK_DISABLE + +#define __ADC12_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET +#define __ADC12_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET +#define __ADC34_FORCE_RESET __HAL_RCC_ADC34_FORCE_RESET +#define __ADC34_RELEASE_RESET __HAL_RCC_ADC34_RELEASE_RESET +#define __DAC2_FORCE_RESET __HAL_RCC_DAC2_FORCE_RESET +#define __DAC2_RELEASE_RESET __HAL_RCC_DAC2_RELEASE_RESET +#define __TIM18_FORCE_RESET __HAL_RCC_TIM18_FORCE_RESET +#define __TIM18_RELEASE_RESET __HAL_RCC_TIM18_RELEASE_RESET +#define __TIM19_FORCE_RESET __HAL_RCC_TIM19_FORCE_RESET +#define __TIM19_RELEASE_RESET __HAL_RCC_TIM19_RELEASE_RESET +#define __TIM20_FORCE_RESET __HAL_RCC_TIM20_FORCE_RESET +#define __TIM20_RELEASE_RESET __HAL_RCC_TIM20_RELEASE_RESET +#define __HRTIM1_FORCE_RESET __HAL_RCC_HRTIM1_FORCE_RESET +#define __HRTIM1_RELEASE_RESET __HAL_RCC_HRTIM1_RELEASE_RESET +#define __SDADC1_FORCE_RESET __HAL_RCC_SDADC1_FORCE_RESET +#define __SDADC2_FORCE_RESET __HAL_RCC_SDADC2_FORCE_RESET +#define __SDADC3_FORCE_RESET __HAL_RCC_SDADC3_FORCE_RESET +#define __SDADC1_RELEASE_RESET __HAL_RCC_SDADC1_RELEASE_RESET +#define __SDADC2_RELEASE_RESET __HAL_RCC_SDADC2_RELEASE_RESET +#define __SDADC3_RELEASE_RESET __HAL_RCC_SDADC3_RELEASE_RESET + +#define __ADC1_IS_CLK_ENABLED __HAL_RCC_ADC1_IS_CLK_ENABLED +#define __ADC1_IS_CLK_DISABLED __HAL_RCC_ADC1_IS_CLK_DISABLED +#define __ADC12_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED +#define __ADC12_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED +#define __ADC34_IS_CLK_ENABLED __HAL_RCC_ADC34_IS_CLK_ENABLED +#define __ADC34_IS_CLK_DISABLED __HAL_RCC_ADC34_IS_CLK_DISABLED +#define __CEC_IS_CLK_ENABLED __HAL_RCC_CEC_IS_CLK_ENABLED +#define __CEC_IS_CLK_DISABLED __HAL_RCC_CEC_IS_CLK_DISABLED +#define __CRC_IS_CLK_ENABLED __HAL_RCC_CRC_IS_CLK_ENABLED +#define __CRC_IS_CLK_DISABLED __HAL_RCC_CRC_IS_CLK_DISABLED +#define __DAC1_IS_CLK_ENABLED __HAL_RCC_DAC1_IS_CLK_ENABLED +#define __DAC1_IS_CLK_DISABLED __HAL_RCC_DAC1_IS_CLK_DISABLED +#define __DAC2_IS_CLK_ENABLED __HAL_RCC_DAC2_IS_CLK_ENABLED +#define __DAC2_IS_CLK_DISABLED __HAL_RCC_DAC2_IS_CLK_DISABLED +#define __DMA1_IS_CLK_ENABLED __HAL_RCC_DMA1_IS_CLK_ENABLED +#define __DMA1_IS_CLK_DISABLED __HAL_RCC_DMA1_IS_CLK_DISABLED +#define __DMA2_IS_CLK_ENABLED __HAL_RCC_DMA2_IS_CLK_ENABLED +#define __DMA2_IS_CLK_DISABLED __HAL_RCC_DMA2_IS_CLK_DISABLED +#define __FLITF_IS_CLK_ENABLED __HAL_RCC_FLITF_IS_CLK_ENABLED +#define __FLITF_IS_CLK_DISABLED __HAL_RCC_FLITF_IS_CLK_DISABLED +#define __FMC_IS_CLK_ENABLED __HAL_RCC_FMC_IS_CLK_ENABLED +#define __FMC_IS_CLK_DISABLED __HAL_RCC_FMC_IS_CLK_DISABLED +#define __GPIOA_IS_CLK_ENABLED __HAL_RCC_GPIOA_IS_CLK_ENABLED +#define __GPIOA_IS_CLK_DISABLED __HAL_RCC_GPIOA_IS_CLK_DISABLED +#define __GPIOB_IS_CLK_ENABLED __HAL_RCC_GPIOB_IS_CLK_ENABLED +#define __GPIOB_IS_CLK_DISABLED __HAL_RCC_GPIOB_IS_CLK_DISABLED +#define __GPIOC_IS_CLK_ENABLED __HAL_RCC_GPIOC_IS_CLK_ENABLED +#define __GPIOC_IS_CLK_DISABLED __HAL_RCC_GPIOC_IS_CLK_DISABLED +#define __GPIOD_IS_CLK_ENABLED __HAL_RCC_GPIOD_IS_CLK_ENABLED +#define __GPIOD_IS_CLK_DISABLED __HAL_RCC_GPIOD_IS_CLK_DISABLED +#define __GPIOE_IS_CLK_ENABLED __HAL_RCC_GPIOE_IS_CLK_ENABLED +#define __GPIOE_IS_CLK_DISABLED __HAL_RCC_GPIOE_IS_CLK_DISABLED +#define __GPIOF_IS_CLK_ENABLED __HAL_RCC_GPIOF_IS_CLK_ENABLED +#define __GPIOF_IS_CLK_DISABLED __HAL_RCC_GPIOF_IS_CLK_DISABLED +#define __GPIOG_IS_CLK_ENABLED __HAL_RCC_GPIOG_IS_CLK_ENABLED +#define __GPIOG_IS_CLK_DISABLED __HAL_RCC_GPIOG_IS_CLK_DISABLED +#define __GPIOH_IS_CLK_ENABLED __HAL_RCC_GPIOH_IS_CLK_ENABLED +#define __GPIOH_IS_CLK_DISABLED __HAL_RCC_GPIOH_IS_CLK_DISABLED +#define __HRTIM1_IS_CLK_ENABLED __HAL_RCC_HRTIM1_IS_CLK_ENABLED +#define __HRTIM1_IS_CLK_DISABLED __HAL_RCC_HRTIM1_IS_CLK_DISABLED +#define __I2C1_IS_CLK_ENABLED __HAL_RCC_I2C1_IS_CLK_ENABLED +#define __I2C1_IS_CLK_DISABLED __HAL_RCC_I2C1_IS_CLK_DISABLED +#define __I2C2_IS_CLK_ENABLED __HAL_RCC_I2C2_IS_CLK_ENABLED +#define __I2C2_IS_CLK_DISABLED __HAL_RCC_I2C2_IS_CLK_DISABLED +#define __I2C3_IS_CLK_ENABLED __HAL_RCC_I2C3_IS_CLK_ENABLED +#define __I2C3_IS_CLK_DISABLED __HAL_RCC_I2C3_IS_CLK_DISABLED +#define __PWR_IS_CLK_ENABLED __HAL_RCC_PWR_IS_CLK_ENABLED +#define __PWR_IS_CLK_DISABLED __HAL_RCC_PWR_IS_CLK_DISABLED +#define __SYSCFG_IS_CLK_ENABLED __HAL_RCC_SYSCFG_IS_CLK_ENABLED +#define __SYSCFG_IS_CLK_DISABLED __HAL_RCC_SYSCFG_IS_CLK_DISABLED +#define __SPI1_IS_CLK_ENABLED __HAL_RCC_SPI1_IS_CLK_ENABLED +#define __SPI1_IS_CLK_DISABLED __HAL_RCC_SPI1_IS_CLK_DISABLED +#define __SPI2_IS_CLK_ENABLED __HAL_RCC_SPI2_IS_CLK_ENABLED +#define __SPI2_IS_CLK_DISABLED __HAL_RCC_SPI2_IS_CLK_DISABLED +#define __SPI3_IS_CLK_ENABLED __HAL_RCC_SPI3_IS_CLK_ENABLED +#define __SPI3_IS_CLK_DISABLED __HAL_RCC_SPI3_IS_CLK_DISABLED +#define __SPI4_IS_CLK_ENABLED __HAL_RCC_SPI4_IS_CLK_ENABLED +#define __SPI4_IS_CLK_DISABLED __HAL_RCC_SPI4_IS_CLK_DISABLED +#define __SDADC1_IS_CLK_ENABLED __HAL_RCC_SDADC1_IS_CLK_ENABLED +#define __SDADC1_IS_CLK_DISABLED __HAL_RCC_SDADC1_IS_CLK_DISABLED +#define __SDADC2_IS_CLK_ENABLED __HAL_RCC_SDADC2_IS_CLK_ENABLED +#define __SDADC2_IS_CLK_DISABLED __HAL_RCC_SDADC2_IS_CLK_DISABLED +#define __SDADC3_IS_CLK_ENABLED __HAL_RCC_SDADC3_IS_CLK_ENABLED +#define __SDADC3_IS_CLK_DISABLED __HAL_RCC_SDADC3_IS_CLK_DISABLED +#define __SRAM_IS_CLK_ENABLED __HAL_RCC_SRAM_IS_CLK_ENABLED +#define __SRAM_IS_CLK_DISABLED __HAL_RCC_SRAM_IS_CLK_DISABLED +#define __TIM1_IS_CLK_ENABLED __HAL_RCC_TIM1_IS_CLK_ENABLED +#define __TIM1_IS_CLK_DISABLED __HAL_RCC_TIM1_IS_CLK_DISABLED +#define __TIM2_IS_CLK_ENABLED __HAL_RCC_TIM2_IS_CLK_ENABLED +#define __TIM2_IS_CLK_DISABLED __HAL_RCC_TIM2_IS_CLK_DISABLED +#define __TIM3_IS_CLK_ENABLED __HAL_RCC_TIM3_IS_CLK_ENABLED +#define __TIM3_IS_CLK_DISABLED __HAL_RCC_TIM3_IS_CLK_DISABLED +#define __TIM4_IS_CLK_ENABLED __HAL_RCC_TIM4_IS_CLK_ENABLED +#define __TIM4_IS_CLK_DISABLED __HAL_RCC_TIM4_IS_CLK_DISABLED +#define __TIM5_IS_CLK_ENABLED __HAL_RCC_TIM5_IS_CLK_ENABLED +#define __TIM5_IS_CLK_DISABLED __HAL_RCC_TIM5_IS_CLK_DISABLED +#define __TIM6_IS_CLK_ENABLED __HAL_RCC_TIM6_IS_CLK_ENABLED +#define __TIM6_IS_CLK_DISABLED __HAL_RCC_TIM6_IS_CLK_DISABLED +#define __TIM7_IS_CLK_ENABLED __HAL_RCC_TIM7_IS_CLK_ENABLED +#define __TIM7_IS_CLK_DISABLED __HAL_RCC_TIM7_IS_CLK_DISABLED +#define __TIM8_IS_CLK_ENABLED __HAL_RCC_TIM8_IS_CLK_ENABLED +#define __TIM8_IS_CLK_DISABLED __HAL_RCC_TIM8_IS_CLK_DISABLED +#define __TIM12_IS_CLK_ENABLED __HAL_RCC_TIM12_IS_CLK_ENABLED +#define __TIM12_IS_CLK_DISABLED __HAL_RCC_TIM12_IS_CLK_DISABLED +#define __TIM13_IS_CLK_ENABLED __HAL_RCC_TIM13_IS_CLK_ENABLED +#define __TIM13_IS_CLK_DISABLED __HAL_RCC_TIM13_IS_CLK_DISABLED +#define __TIM14_IS_CLK_ENABLED __HAL_RCC_TIM14_IS_CLK_ENABLED +#define __TIM14_IS_CLK_DISABLED __HAL_RCC_TIM14_IS_CLK_DISABLED +#define __TIM15_IS_CLK_ENABLED __HAL_RCC_TIM15_IS_CLK_ENABLED +#define __TIM15_IS_CLK_DISABLED __HAL_RCC_TIM15_IS_CLK_DISABLED +#define __TIM16_IS_CLK_ENABLED __HAL_RCC_TIM16_IS_CLK_ENABLED +#define __TIM16_IS_CLK_DISABLED __HAL_RCC_TIM16_IS_CLK_DISABLED +#define __TIM17_IS_CLK_ENABLED __HAL_RCC_TIM17_IS_CLK_ENABLED +#define __TIM17_IS_CLK_DISABLED __HAL_RCC_TIM17_IS_CLK_DISABLED +#define __TIM18_IS_CLK_ENABLED __HAL_RCC_TIM18_IS_CLK_ENABLED +#define __TIM18_IS_CLK_DISABLED __HAL_RCC_TIM18_IS_CLK_DISABLED +#define __TIM19_IS_CLK_ENABLED __HAL_RCC_TIM19_IS_CLK_ENABLED +#define __TIM19_IS_CLK_DISABLED __HAL_RCC_TIM19_IS_CLK_DISABLED +#define __TIM20_IS_CLK_ENABLED __HAL_RCC_TIM20_IS_CLK_ENABLED +#define __TIM20_IS_CLK_DISABLED __HAL_RCC_TIM20_IS_CLK_DISABLED +#define __TSC_IS_CLK_ENABLED __HAL_RCC_TSC_IS_CLK_ENABLED +#define __TSC_IS_CLK_DISABLED __HAL_RCC_TSC_IS_CLK_DISABLED +#define __UART4_IS_CLK_ENABLED __HAL_RCC_UART4_IS_CLK_ENABLED +#define __UART4_IS_CLK_DISABLED __HAL_RCC_UART4_IS_CLK_DISABLED +#define __UART5_IS_CLK_ENABLED __HAL_RCC_UART5_IS_CLK_ENABLED +#define __UART5_IS_CLK_DISABLED __HAL_RCC_UART5_IS_CLK_DISABLED +#define __USART1_IS_CLK_ENABLED __HAL_RCC_USART1_IS_CLK_ENABLED +#define __USART1_IS_CLK_DISABLED __HAL_RCC_USART1_IS_CLK_DISABLED +#define __USART2_IS_CLK_ENABLED __HAL_RCC_USART2_IS_CLK_ENABLED +#define __USART2_IS_CLK_DISABLED __HAL_RCC_USART2_IS_CLK_DISABLED +#define __USART3_IS_CLK_ENABLED __HAL_RCC_USART3_IS_CLK_ENABLED +#define __USART3_IS_CLK_DISABLED __HAL_RCC_USART3_IS_CLK_DISABLED +#define __USB_IS_CLK_ENABLED __HAL_RCC_USB_IS_CLK_ENABLED +#define __USB_IS_CLK_DISABLED __HAL_RCC_USB_IS_CLK_DISABLED +#define __WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG_IS_CLK_ENABLED +#define __WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG_IS_CLK_DISABLED + +#if defined(STM32L1) +#define __HAL_RCC_CRYP_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE +#define __HAL_RCC_CRYP_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE +#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE +#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE +#define __HAL_RCC_CRYP_FORCE_RESET __HAL_RCC_AES_FORCE_RESET +#define __HAL_RCC_CRYP_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET +#endif /* STM32L1 */ + +#if defined(STM32F4) +#define __HAL_RCC_SDMMC1_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET +#define __HAL_RCC_SDMMC1_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET +#define __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE +#define __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE +#define __HAL_RCC_SDMMC1_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE +#define __HAL_RCC_SDMMC1_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE +#define __HAL_RCC_SDMMC1_IS_CLK_ENABLED __HAL_RCC_SDIO_IS_CLK_ENABLED +#define __HAL_RCC_SDMMC1_IS_CLK_DISABLED __HAL_RCC_SDIO_IS_CLK_DISABLED +#define Sdmmc1ClockSelection SdioClockSelection +#define RCC_PERIPHCLK_SDMMC1 RCC_PERIPHCLK_SDIO +#define RCC_SDMMC1CLKSOURCE_CLK48 RCC_SDIOCLKSOURCE_CK48 +#define RCC_SDMMC1CLKSOURCE_SYSCLK RCC_SDIOCLKSOURCE_SYSCLK +#define __HAL_RCC_SDMMC1_CONFIG __HAL_RCC_SDIO_CONFIG +#define __HAL_RCC_GET_SDMMC1_SOURCE __HAL_RCC_GET_SDIO_SOURCE +#endif + +#if defined(STM32F7) || defined(STM32L4) +#define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET +#define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE +#define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE +#define __HAL_RCC_SDIO_CLK_DISABLE __HAL_RCC_SDMMC1_CLK_DISABLE +#define __HAL_RCC_SDIO_IS_CLK_ENABLED __HAL_RCC_SDMMC1_IS_CLK_ENABLED +#define __HAL_RCC_SDIO_IS_CLK_DISABLED __HAL_RCC_SDMMC1_IS_CLK_DISABLED +#define SdioClockSelection Sdmmc1ClockSelection +#define RCC_PERIPHCLK_SDIO RCC_PERIPHCLK_SDMMC1 +#define __HAL_RCC_SDIO_CONFIG __HAL_RCC_SDMMC1_CONFIG +#define __HAL_RCC_GET_SDIO_SOURCE __HAL_RCC_GET_SDMMC1_SOURCE +#endif + +#if defined(STM32F7) +#define RCC_SDIOCLKSOURCE_CLK48 RCC_SDMMC1CLKSOURCE_CLK48 +#define RCC_SDIOCLKSOURCE_SYSCLK RCC_SDMMC1CLKSOURCE_SYSCLK +#endif + +#if defined(STM32H7) +#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_ENABLE() +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE() +#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_DISABLE() +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE() +#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() __HAL_RCC_USB1_OTG_HS_FORCE_RESET() +#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() __HAL_RCC_USB1_OTG_HS_RELEASE_RESET() +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_ENABLE() +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_ENABLE() +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_DISABLE() +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_DISABLE() + +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_ENABLE() +#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_ENABLE() +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_DISABLE() +#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_DISABLE() +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() __HAL_RCC_USB2_OTG_FS_FORCE_RESET() +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() __HAL_RCC_USB2_OTG_FS_RELEASE_RESET() +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_ENABLE() +#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_ENABLE() +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_DISABLE() +#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_DISABLE() +#endif + +#define __HAL_RCC_I2SCLK __HAL_RCC_I2S_CONFIG +#define __HAL_RCC_I2SCLK_CONFIG __HAL_RCC_I2S_CONFIG + +#define __RCC_PLLSRC RCC_GET_PLL_OSCSOURCE + +#define IS_RCC_MSIRANGE IS_RCC_MSI_CLOCK_RANGE +#define IS_RCC_RTCCLK_SOURCE IS_RCC_RTCCLKSOURCE +#define IS_RCC_SYSCLK_DIV IS_RCC_HCLK +#define IS_RCC_HCLK_DIV IS_RCC_PCLK +#define IS_RCC_PERIPHCLK IS_RCC_PERIPHCLOCK + +#define RCC_IT_HSI14 RCC_IT_HSI14RDY + +#define RCC_IT_CSSLSE RCC_IT_LSECSS +#define RCC_IT_CSSHSE RCC_IT_CSS + +#define RCC_PLLMUL_3 RCC_PLL_MUL3 +#define RCC_PLLMUL_4 RCC_PLL_MUL4 +#define RCC_PLLMUL_6 RCC_PLL_MUL6 +#define RCC_PLLMUL_8 RCC_PLL_MUL8 +#define RCC_PLLMUL_12 RCC_PLL_MUL12 +#define RCC_PLLMUL_16 RCC_PLL_MUL16 +#define RCC_PLLMUL_24 RCC_PLL_MUL24 +#define RCC_PLLMUL_32 RCC_PLL_MUL32 +#define RCC_PLLMUL_48 RCC_PLL_MUL48 + +#define RCC_PLLDIV_2 RCC_PLL_DIV2 +#define RCC_PLLDIV_3 RCC_PLL_DIV3 +#define RCC_PLLDIV_4 RCC_PLL_DIV4 + +#define IS_RCC_MCOSOURCE IS_RCC_MCO1SOURCE +#define __HAL_RCC_MCO_CONFIG __HAL_RCC_MCO1_CONFIG +#define RCC_MCO_NODIV RCC_MCODIV_1 +#define RCC_MCO_DIV1 RCC_MCODIV_1 +#define RCC_MCO_DIV2 RCC_MCODIV_2 +#define RCC_MCO_DIV4 RCC_MCODIV_4 +#define RCC_MCO_DIV8 RCC_MCODIV_8 +#define RCC_MCO_DIV16 RCC_MCODIV_16 +#define RCC_MCO_DIV32 RCC_MCODIV_32 +#define RCC_MCO_DIV64 RCC_MCODIV_64 +#define RCC_MCO_DIV128 RCC_MCODIV_128 +#define RCC_MCOSOURCE_NONE RCC_MCO1SOURCE_NOCLOCK +#define RCC_MCOSOURCE_LSI RCC_MCO1SOURCE_LSI +#define RCC_MCOSOURCE_LSE RCC_MCO1SOURCE_LSE +#define RCC_MCOSOURCE_SYSCLK RCC_MCO1SOURCE_SYSCLK +#define RCC_MCOSOURCE_HSI RCC_MCO1SOURCE_HSI +#define RCC_MCOSOURCE_HSI14 RCC_MCO1SOURCE_HSI14 +#define RCC_MCOSOURCE_HSI48 RCC_MCO1SOURCE_HSI48 +#define RCC_MCOSOURCE_HSE RCC_MCO1SOURCE_HSE +#define RCC_MCOSOURCE_PLLCLK_DIV1 RCC_MCO1SOURCE_PLLCLK +#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK +#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2 + +#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || defined(STM32WL) || defined(STM32C0) +#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE +#else +#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK +#endif + +#define RCC_USBCLK_PLLSAI1 RCC_USBCLKSOURCE_PLLSAI1 +#define RCC_USBCLK_PLL RCC_USBCLKSOURCE_PLL +#define RCC_USBCLK_MSI RCC_USBCLKSOURCE_MSI +#define RCC_USBCLKSOURCE_PLLCLK RCC_USBCLKSOURCE_PLL +#define RCC_USBPLLCLK_DIV1 RCC_USBCLKSOURCE_PLL +#define RCC_USBPLLCLK_DIV1_5 RCC_USBCLKSOURCE_PLL_DIV1_5 +#define RCC_USBPLLCLK_DIV2 RCC_USBCLKSOURCE_PLL_DIV2 +#define RCC_USBPLLCLK_DIV3 RCC_USBCLKSOURCE_PLL_DIV3 + +#define HSION_BitNumber RCC_HSION_BIT_NUMBER +#define HSION_BITNUMBER RCC_HSION_BIT_NUMBER +#define HSEON_BitNumber RCC_HSEON_BIT_NUMBER +#define HSEON_BITNUMBER RCC_HSEON_BIT_NUMBER +#define MSION_BITNUMBER RCC_MSION_BIT_NUMBER +#define CSSON_BitNumber RCC_CSSON_BIT_NUMBER +#define CSSON_BITNUMBER RCC_CSSON_BIT_NUMBER +#define PLLON_BitNumber RCC_PLLON_BIT_NUMBER +#define PLLON_BITNUMBER RCC_PLLON_BIT_NUMBER +#define PLLI2SON_BitNumber RCC_PLLI2SON_BIT_NUMBER +#define I2SSRC_BitNumber RCC_I2SSRC_BIT_NUMBER +#define RTCEN_BitNumber RCC_RTCEN_BIT_NUMBER +#define RTCEN_BITNUMBER RCC_RTCEN_BIT_NUMBER +#define BDRST_BitNumber RCC_BDRST_BIT_NUMBER +#define BDRST_BITNUMBER RCC_BDRST_BIT_NUMBER +#define RTCRST_BITNUMBER RCC_RTCRST_BIT_NUMBER +#define LSION_BitNumber RCC_LSION_BIT_NUMBER +#define LSION_BITNUMBER RCC_LSION_BIT_NUMBER +#define LSEON_BitNumber RCC_LSEON_BIT_NUMBER +#define LSEON_BITNUMBER RCC_LSEON_BIT_NUMBER +#define LSEBYP_BITNUMBER RCC_LSEBYP_BIT_NUMBER +#define PLLSAION_BitNumber RCC_PLLSAION_BIT_NUMBER +#define TIMPRE_BitNumber RCC_TIMPRE_BIT_NUMBER +#define RMVF_BitNumber RCC_RMVF_BIT_NUMBER +#define RMVF_BITNUMBER RCC_RMVF_BIT_NUMBER +#define RCC_CR2_HSI14TRIM_BitNumber RCC_HSI14TRIM_BIT_NUMBER +#define CR_BYTE2_ADDRESS RCC_CR_BYTE2_ADDRESS +#define CIR_BYTE1_ADDRESS RCC_CIR_BYTE1_ADDRESS +#define CIR_BYTE2_ADDRESS RCC_CIR_BYTE2_ADDRESS +#define BDCR_BYTE0_ADDRESS RCC_BDCR_BYTE0_ADDRESS +#define DBP_TIMEOUT_VALUE RCC_DBP_TIMEOUT_VALUE +#define LSE_TIMEOUT_VALUE RCC_LSE_TIMEOUT_VALUE + +#define CR_HSION_BB RCC_CR_HSION_BB +#define CR_CSSON_BB RCC_CR_CSSON_BB +#define CR_PLLON_BB RCC_CR_PLLON_BB +#define CR_PLLI2SON_BB RCC_CR_PLLI2SON_BB +#define CR_MSION_BB RCC_CR_MSION_BB +#define CSR_LSION_BB RCC_CSR_LSION_BB +#define CSR_LSEON_BB RCC_CSR_LSEON_BB +#define CSR_LSEBYP_BB RCC_CSR_LSEBYP_BB +#define CSR_RTCEN_BB RCC_CSR_RTCEN_BB +#define CSR_RTCRST_BB RCC_CSR_RTCRST_BB +#define CFGR_I2SSRC_BB RCC_CFGR_I2SSRC_BB +#define BDCR_RTCEN_BB RCC_BDCR_RTCEN_BB +#define BDCR_BDRST_BB RCC_BDCR_BDRST_BB +#define CR_HSEON_BB RCC_CR_HSEON_BB +#define CSR_RMVF_BB RCC_CSR_RMVF_BB +#define CR_PLLSAION_BB RCC_CR_PLLSAION_BB +#define DCKCFGR_TIMPRE_BB RCC_DCKCFGR_TIMPRE_BB + +#define __HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE +#define __HAL_RCC_CRS_DISABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE +#define __HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE +#define __HAL_RCC_CRS_DISABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE +#define __HAL_RCC_CRS_CALCULATE_RELOADVALUE __HAL_RCC_CRS_RELOADVALUE_CALCULATE + +#define __HAL_RCC_GET_IT_SOURCE __HAL_RCC_GET_IT + +#define RCC_CRS_SYNCWARM RCC_CRS_SYNCWARN +#define RCC_CRS_TRIMOV RCC_CRS_TRIMOVF + +#define RCC_PERIPHCLK_CK48 RCC_PERIPHCLK_CLK48 +#define RCC_CK48CLKSOURCE_PLLQ RCC_CLK48CLKSOURCE_PLLQ +#define RCC_CK48CLKSOURCE_PLLSAIP RCC_CLK48CLKSOURCE_PLLSAIP +#define RCC_CK48CLKSOURCE_PLLI2SQ RCC_CLK48CLKSOURCE_PLLI2SQ +#define IS_RCC_CK48CLKSOURCE IS_RCC_CLK48CLKSOURCE +#define RCC_SDIOCLKSOURCE_CK48 RCC_SDIOCLKSOURCE_CLK48 + +#define __HAL_RCC_DFSDM_CLK_ENABLE __HAL_RCC_DFSDM1_CLK_ENABLE +#define __HAL_RCC_DFSDM_CLK_DISABLE __HAL_RCC_DFSDM1_CLK_DISABLE +#define __HAL_RCC_DFSDM_IS_CLK_ENABLED __HAL_RCC_DFSDM1_IS_CLK_ENABLED +#define __HAL_RCC_DFSDM_IS_CLK_DISABLED __HAL_RCC_DFSDM1_IS_CLK_DISABLED +#define __HAL_RCC_DFSDM_FORCE_RESET __HAL_RCC_DFSDM1_FORCE_RESET +#define __HAL_RCC_DFSDM_RELEASE_RESET __HAL_RCC_DFSDM1_RELEASE_RESET +#define __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE +#define __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE +#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_ENABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_ENABLED +#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_DISABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_DISABLED +#define DfsdmClockSelection Dfsdm1ClockSelection +#define RCC_PERIPHCLK_DFSDM RCC_PERIPHCLK_DFSDM1 +#define RCC_DFSDMCLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 +#define RCC_DFSDMCLKSOURCE_SYSCLK RCC_DFSDM1CLKSOURCE_SYSCLK +#define __HAL_RCC_DFSDM_CONFIG __HAL_RCC_DFSDM1_CONFIG +#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE +#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 +#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1 +#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1 +#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1 + +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1 +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2 +#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM2AUDIOCLKSOURCE_I2S1 +#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM2AUDIOCLKSOURCE_I2S2 +#define RCC_DFSDM1CLKSOURCE_APB2 RCC_DFSDM1CLKSOURCE_PCLK2 +#define RCC_DFSDM2CLKSOURCE_APB2 RCC_DFSDM2CLKSOURCE_PCLK2 +#define RCC_FMPI2C1CLKSOURCE_APB RCC_FMPI2C1CLKSOURCE_PCLK1 +#if defined(STM32U5) +#define MSIKPLLModeSEL RCC_MSIKPLL_MODE_SEL +#define MSISPLLModeSEL RCC_MSISPLL_MODE_SEL +#define __HAL_RCC_AHB21_CLK_DISABLE __HAL_RCC_AHB2_1_CLK_DISABLE +#define __HAL_RCC_AHB22_CLK_DISABLE __HAL_RCC_AHB2_2_CLK_DISABLE +#define __HAL_RCC_AHB1_CLK_Disable_Clear __HAL_RCC_AHB1_CLK_ENABLE +#define __HAL_RCC_AHB21_CLK_Disable_Clear __HAL_RCC_AHB2_1_CLK_ENABLE +#define __HAL_RCC_AHB22_CLK_Disable_Clear __HAL_RCC_AHB2_2_CLK_ENABLE +#define __HAL_RCC_AHB3_CLK_Disable_Clear __HAL_RCC_AHB3_CLK_ENABLE +#define __HAL_RCC_APB1_CLK_Disable_Clear __HAL_RCC_APB1_CLK_ENABLE +#define __HAL_RCC_APB2_CLK_Disable_Clear __HAL_RCC_APB2_CLK_ENABLE +#define __HAL_RCC_APB3_CLK_Disable_Clear __HAL_RCC_APB3_CLK_ENABLE +#define IS_RCC_MSIPLLModeSelection IS_RCC_MSIPLLMODE_SELECT +#define RCC_PERIPHCLK_CLK48 RCC_PERIPHCLK_ICLK +#define RCC_CLK48CLKSOURCE_HSI48 RCC_ICLK_CLKSOURCE_HSI48 +#define RCC_CLK48CLKSOURCE_PLL2 RCC_ICLK_CLKSOURCE_PLL2 +#define RCC_CLK48CLKSOURCE_PLL1 RCC_ICLK_CLKSOURCE_PLL1 +#define RCC_CLK48CLKSOURCE_MSIK RCC_ICLK_CLKSOURCE_MSIK +#define __HAL_RCC_ADC1_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE +#define __HAL_RCC_ADC1_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE +#define __HAL_RCC_ADC1_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED +#define __HAL_RCC_ADC1_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED +#define __HAL_RCC_ADC1_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET +#define __HAL_RCC_ADC1_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET +#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC12_CLK_SLEEP_ENABLE +#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC12_CLK_SLEEP_DISABLE +#define __HAL_RCC_GET_CLK48_SOURCE __HAL_RCC_GET_ICLK_SOURCE +#define __HAL_RCC_PLLFRACN_ENABLE __HAL_RCC_PLL_FRACN_ENABLE +#define __HAL_RCC_PLLFRACN_DISABLE __HAL_RCC_PLL_FRACN_DISABLE +#define __HAL_RCC_PLLFRACN_CONFIG __HAL_RCC_PLL_FRACN_CONFIG +#define IS_RCC_PLLFRACN_VALUE IS_RCC_PLL_FRACN_VALUE +#endif /* STM32U5 */ + +/** + * @} + */ + +/** @defgroup HAL_RNG_Aliased_Macros HAL RNG Aliased Macros maintained for legacy purpose + * @{ + */ +#define HAL_RNG_ReadyCallback(__HANDLE__) HAL_RNG_ReadyDataCallback((__HANDLE__), uint32_t random32bit) + +/** + * @} + */ + +/** @defgroup HAL_RTC_Aliased_Macros HAL RTC Aliased Macros maintained for legacy purpose + * @{ + */ +#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || defined (STM32L4P5xx)|| \ + defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) || \ + defined (STM32C0) +#else +#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG +#endif +#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT +#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT + +#if defined (STM32F1) +#define __HAL_RTC_EXTI_CLEAR_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() + +#define __HAL_RTC_EXTI_ENABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_ENABLE_IT() + +#define __HAL_RTC_EXTI_DISABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_DISABLE_IT() + +#define __HAL_RTC_EXTI_GET_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GET_FLAG() + +#define __HAL_RTC_EXTI_GENERATE_SWIT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() +#else +#define __HAL_RTC_EXTI_CLEAR_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() : \ + (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() : \ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG())) +#define __HAL_RTC_EXTI_ENABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_ENABLE_IT() : \ + (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() : \ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT())) +#define __HAL_RTC_EXTI_DISABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_DISABLE_IT() : \ + (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() : \ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT())) +#define __HAL_RTC_EXTI_GET_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GET_FLAG() : \ + (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() : \ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG())) +#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() : \ + (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() : \ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT())) +#endif /* STM32F1 */ + +#define IS_ALARM IS_RTC_ALARM +#define IS_ALARM_MASK IS_RTC_ALARM_MASK +#define IS_TAMPER IS_RTC_TAMPER +#define IS_TAMPER_ERASE_MODE IS_RTC_TAMPER_ERASE_MODE +#define IS_TAMPER_FILTER IS_RTC_TAMPER_FILTER +#define IS_TAMPER_INTERRUPT IS_RTC_TAMPER_INTERRUPT +#define IS_TAMPER_MASKFLAG_STATE IS_RTC_TAMPER_MASKFLAG_STATE +#define IS_TAMPER_PRECHARGE_DURATION IS_RTC_TAMPER_PRECHARGE_DURATION +#define IS_TAMPER_PULLUP_STATE IS_RTC_TAMPER_PULLUP_STATE +#define IS_TAMPER_SAMPLING_FREQ IS_RTC_TAMPER_SAMPLING_FREQ +#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION +#define IS_TAMPER_TRIGGER IS_RTC_TAMPER_TRIGGER +#define IS_WAKEUP_CLOCK IS_RTC_WAKEUP_CLOCK +#define IS_WAKEUP_COUNTER IS_RTC_WAKEUP_COUNTER + +#define __RTC_WRITEPROTECTION_ENABLE __HAL_RTC_WRITEPROTECTION_ENABLE +#define __RTC_WRITEPROTECTION_DISABLE __HAL_RTC_WRITEPROTECTION_DISABLE + +/** + * @} + */ + +/** @defgroup HAL_SD_Aliased_Macros HAL SD/MMC Aliased Macros maintained for legacy purpose + * @{ + */ + +#define SD_OCR_CID_CSD_OVERWRIETE SD_OCR_CID_CSD_OVERWRITE +#define SD_CMD_SD_APP_STAUS SD_CMD_SD_APP_STATUS + +#if !defined(STM32F1) && !defined(STM32F2) && !defined(STM32F4) && !defined(STM32L1) +#define eMMC_HIGH_VOLTAGE_RANGE EMMC_HIGH_VOLTAGE_RANGE +#define eMMC_DUAL_VOLTAGE_RANGE EMMC_DUAL_VOLTAGE_RANGE +#define eMMC_LOW_VOLTAGE_RANGE EMMC_LOW_VOLTAGE_RANGE + +#define SDMMC_NSpeed_CLK_DIV SDMMC_NSPEED_CLK_DIV +#define SDMMC_HSpeed_CLK_DIV SDMMC_HSPEED_CLK_DIV +#endif + +#if defined(STM32F4) || defined(STM32F2) +#define SD_SDMMC_DISABLED SD_SDIO_DISABLED +#define SD_SDMMC_FUNCTION_BUSY SD_SDIO_FUNCTION_BUSY +#define SD_SDMMC_FUNCTION_FAILED SD_SDIO_FUNCTION_FAILED +#define SD_SDMMC_UNKNOWN_FUNCTION SD_SDIO_UNKNOWN_FUNCTION +#define SD_CMD_SDMMC_SEN_OP_COND SD_CMD_SDIO_SEN_OP_COND +#define SD_CMD_SDMMC_RW_DIRECT SD_CMD_SDIO_RW_DIRECT +#define SD_CMD_SDMMC_RW_EXTENDED SD_CMD_SDIO_RW_EXTENDED +#define __HAL_SD_SDMMC_ENABLE __HAL_SD_SDIO_ENABLE +#define __HAL_SD_SDMMC_DISABLE __HAL_SD_SDIO_DISABLE +#define __HAL_SD_SDMMC_DMA_ENABLE __HAL_SD_SDIO_DMA_ENABLE +#define __HAL_SD_SDMMC_DMA_DISABLE __HAL_SD_SDIO_DMA_DISABL +#define __HAL_SD_SDMMC_ENABLE_IT __HAL_SD_SDIO_ENABLE_IT +#define __HAL_SD_SDMMC_DISABLE_IT __HAL_SD_SDIO_DISABLE_IT +#define __HAL_SD_SDMMC_GET_FLAG __HAL_SD_SDIO_GET_FLAG +#define __HAL_SD_SDMMC_CLEAR_FLAG __HAL_SD_SDIO_CLEAR_FLAG +#define __HAL_SD_SDMMC_GET_IT __HAL_SD_SDIO_GET_IT +#define __HAL_SD_SDMMC_CLEAR_IT __HAL_SD_SDIO_CLEAR_IT +#define SDMMC_STATIC_FLAGS SDIO_STATIC_FLAGS +#define SDMMC_CMD0TIMEOUT SDIO_CMD0TIMEOUT +#define SD_SDMMC_SEND_IF_COND SD_SDIO_SEND_IF_COND +/* alias CMSIS */ +#define SDMMC1_IRQn SDIO_IRQn +#define SDMMC1_IRQHandler SDIO_IRQHandler +#endif + +#if defined(STM32F7) || defined(STM32L4) +#define SD_SDIO_DISABLED SD_SDMMC_DISABLED +#define SD_SDIO_FUNCTION_BUSY SD_SDMMC_FUNCTION_BUSY +#define SD_SDIO_FUNCTION_FAILED SD_SDMMC_FUNCTION_FAILED +#define SD_SDIO_UNKNOWN_FUNCTION SD_SDMMC_UNKNOWN_FUNCTION +#define SD_CMD_SDIO_SEN_OP_COND SD_CMD_SDMMC_SEN_OP_COND +#define SD_CMD_SDIO_RW_DIRECT SD_CMD_SDMMC_RW_DIRECT +#define SD_CMD_SDIO_RW_EXTENDED SD_CMD_SDMMC_RW_EXTENDED +#define __HAL_SD_SDIO_ENABLE __HAL_SD_SDMMC_ENABLE +#define __HAL_SD_SDIO_DISABLE __HAL_SD_SDMMC_DISABLE +#define __HAL_SD_SDIO_DMA_ENABLE __HAL_SD_SDMMC_DMA_ENABLE +#define __HAL_SD_SDIO_DMA_DISABL __HAL_SD_SDMMC_DMA_DISABLE +#define __HAL_SD_SDIO_ENABLE_IT __HAL_SD_SDMMC_ENABLE_IT +#define __HAL_SD_SDIO_DISABLE_IT __HAL_SD_SDMMC_DISABLE_IT +#define __HAL_SD_SDIO_GET_FLAG __HAL_SD_SDMMC_GET_FLAG +#define __HAL_SD_SDIO_CLEAR_FLAG __HAL_SD_SDMMC_CLEAR_FLAG +#define __HAL_SD_SDIO_GET_IT __HAL_SD_SDMMC_GET_IT +#define __HAL_SD_SDIO_CLEAR_IT __HAL_SD_SDMMC_CLEAR_IT +#define SDIO_STATIC_FLAGS SDMMC_STATIC_FLAGS +#define SDIO_CMD0TIMEOUT SDMMC_CMD0TIMEOUT +#define SD_SDIO_SEND_IF_COND SD_SDMMC_SEND_IF_COND +/* alias CMSIS for compatibilities */ +#define SDIO_IRQn SDMMC1_IRQn +#define SDIO_IRQHandler SDMMC1_IRQHandler +#endif + +#if defined(STM32F7) || defined(STM32F4) || defined(STM32F2) || defined(STM32L4) || defined(STM32H7) +#define HAL_SD_CardCIDTypedef HAL_SD_CardCIDTypeDef +#define HAL_SD_CardCSDTypedef HAL_SD_CardCSDTypeDef +#define HAL_SD_CardStatusTypedef HAL_SD_CardStatusTypeDef +#define HAL_SD_CardStateTypedef HAL_SD_CardStateTypeDef +#endif + +#if defined(STM32H7) || defined(STM32L5) +#define HAL_MMCEx_Read_DMADoubleBuffer0CpltCallback HAL_MMCEx_Read_DMADoubleBuf0CpltCallback +#define HAL_MMCEx_Read_DMADoubleBuffer1CpltCallback HAL_MMCEx_Read_DMADoubleBuf1CpltCallback +#define HAL_MMCEx_Write_DMADoubleBuffer0CpltCallback HAL_MMCEx_Write_DMADoubleBuf0CpltCallback +#define HAL_MMCEx_Write_DMADoubleBuffer1CpltCallback HAL_MMCEx_Write_DMADoubleBuf1CpltCallback +#define HAL_SDEx_Read_DMADoubleBuffer0CpltCallback HAL_SDEx_Read_DMADoubleBuf0CpltCallback +#define HAL_SDEx_Read_DMADoubleBuffer1CpltCallback HAL_SDEx_Read_DMADoubleBuf1CpltCallback +#define HAL_SDEx_Write_DMADoubleBuffer0CpltCallback HAL_SDEx_Write_DMADoubleBuf0CpltCallback +#define HAL_SDEx_Write_DMADoubleBuffer1CpltCallback HAL_SDEx_Write_DMADoubleBuf1CpltCallback +#define HAL_SD_DriveTransciver_1_8V_Callback HAL_SD_DriveTransceiver_1_8V_Callback +#endif +/** + * @} + */ + +/** @defgroup HAL_SMARTCARD_Aliased_Macros HAL SMARTCARD Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __SMARTCARD_ENABLE_IT __HAL_SMARTCARD_ENABLE_IT +#define __SMARTCARD_DISABLE_IT __HAL_SMARTCARD_DISABLE_IT +#define __SMARTCARD_ENABLE __HAL_SMARTCARD_ENABLE +#define __SMARTCARD_DISABLE __HAL_SMARTCARD_DISABLE +#define __SMARTCARD_DMA_REQUEST_ENABLE __HAL_SMARTCARD_DMA_REQUEST_ENABLE +#define __SMARTCARD_DMA_REQUEST_DISABLE __HAL_SMARTCARD_DMA_REQUEST_DISABLE + +#define __HAL_SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE +#define __SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE + +#define IS_SMARTCARD_ONEBIT_SAMPLING IS_SMARTCARD_ONE_BIT_SAMPLE + +/** + * @} + */ + +/** @defgroup HAL_SMBUS_Aliased_Macros HAL SMBUS Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_SMBUS_RESET_CR1 SMBUS_RESET_CR1 +#define __HAL_SMBUS_RESET_CR2 SMBUS_RESET_CR2 +#define __HAL_SMBUS_GENERATE_START SMBUS_GENERATE_START +#define __HAL_SMBUS_GET_ADDR_MATCH SMBUS_GET_ADDR_MATCH +#define __HAL_SMBUS_GET_DIR SMBUS_GET_DIR +#define __HAL_SMBUS_GET_STOP_MODE SMBUS_GET_STOP_MODE +#define __HAL_SMBUS_GET_PEC_MODE SMBUS_GET_PEC_MODE +#define __HAL_SMBUS_GET_ALERT_ENABLED SMBUS_GET_ALERT_ENABLED +/** + * @} + */ + +/** @defgroup HAL_SPI_Aliased_Macros HAL SPI Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __HAL_SPI_1LINE_TX SPI_1LINE_TX +#define __HAL_SPI_1LINE_RX SPI_1LINE_RX +#define __HAL_SPI_RESET_CRC SPI_RESET_CRC + +/** + * @} + */ + +/** @defgroup HAL_UART_Aliased_Macros HAL UART Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __HAL_UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE +#define __HAL_UART_MASK_COMPUTATION UART_MASK_COMPUTATION +#define __UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE +#define __UART_MASK_COMPUTATION UART_MASK_COMPUTATION + +#define IS_UART_WAKEUPMETHODE IS_UART_WAKEUPMETHOD + +#define IS_UART_ONEBIT_SAMPLE IS_UART_ONE_BIT_SAMPLE +#define IS_UART_ONEBIT_SAMPLING IS_UART_ONE_BIT_SAMPLE + +/** + * @} + */ + + +/** @defgroup HAL_USART_Aliased_Macros HAL USART Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __USART_ENABLE_IT __HAL_USART_ENABLE_IT +#define __USART_DISABLE_IT __HAL_USART_DISABLE_IT +#define __USART_ENABLE __HAL_USART_ENABLE +#define __USART_DISABLE __HAL_USART_DISABLE + +#define __HAL_USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE +#define __USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE + +#if defined(STM32F0) || defined(STM32F3) || defined(STM32F7) +#define USART_OVERSAMPLING_16 0x00000000U +#define USART_OVERSAMPLING_8 USART_CR1_OVER8 + +#define IS_USART_OVERSAMPLING(__SAMPLING__) (((__SAMPLING__) == USART_OVERSAMPLING_16) || \ + ((__SAMPLING__) == USART_OVERSAMPLING_8)) +#endif /* STM32F0 || STM32F3 || STM32F7 */ +/** + * @} + */ + +/** @defgroup HAL_USB_Aliased_Macros HAL USB Aliased Macros maintained for legacy purpose + * @{ + */ +#define USB_EXTI_LINE_WAKEUP USB_WAKEUP_EXTI_LINE + +#define USB_FS_EXTI_TRIGGER_RISING_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_EDGE +#define USB_FS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_FS_WAKEUP_EXTI_FALLING_EDGE +#define USB_FS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_FALLING_EDGE +#define USB_FS_EXTI_LINE_WAKEUP USB_OTG_FS_WAKEUP_EXTI_LINE + +#define USB_HS_EXTI_TRIGGER_RISING_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_EDGE +#define USB_HS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_HS_WAKEUP_EXTI_FALLING_EDGE +#define USB_HS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_FALLING_EDGE +#define USB_HS_EXTI_LINE_WAKEUP USB_OTG_HS_WAKEUP_EXTI_LINE + +#define __HAL_USB_EXTI_ENABLE_IT __HAL_USB_WAKEUP_EXTI_ENABLE_IT +#define __HAL_USB_EXTI_DISABLE_IT __HAL_USB_WAKEUP_EXTI_DISABLE_IT +#define __HAL_USB_EXTI_GET_FLAG __HAL_USB_WAKEUP_EXTI_GET_FLAG +#define __HAL_USB_EXTI_CLEAR_FLAG __HAL_USB_WAKEUP_EXTI_CLEAR_FLAG +#define __HAL_USB_EXTI_SET_RISING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_EDGE +#define __HAL_USB_EXTI_SET_FALLING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_FALLING_EDGE +#define __HAL_USB_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE + +#define __HAL_USB_FS_EXTI_ENABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT +#define __HAL_USB_FS_EXTI_DISABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT +#define __HAL_USB_FS_EXTI_GET_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG +#define __HAL_USB_FS_EXTI_CLEAR_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG +#define __HAL_USB_FS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE +#define __HAL_USB_FS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_FALLING_EDGE +#define __HAL_USB_FS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE +#define __HAL_USB_FS_EXTI_GENERATE_SWIT __HAL_USB_OTG_FS_WAKEUP_EXTI_GENERATE_SWIT + +#define __HAL_USB_HS_EXTI_ENABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT +#define __HAL_USB_HS_EXTI_DISABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT +#define __HAL_USB_HS_EXTI_GET_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG +#define __HAL_USB_HS_EXTI_CLEAR_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG +#define __HAL_USB_HS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE +#define __HAL_USB_HS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_FALLING_EDGE +#define __HAL_USB_HS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE +#define __HAL_USB_HS_EXTI_GENERATE_SWIT __HAL_USB_OTG_HS_WAKEUP_EXTI_GENERATE_SWIT + +#define HAL_PCD_ActiveRemoteWakeup HAL_PCD_ActivateRemoteWakeup +#define HAL_PCD_DeActiveRemoteWakeup HAL_PCD_DeActivateRemoteWakeup + +#define HAL_PCD_SetTxFiFo HAL_PCDEx_SetTxFiFo +#define HAL_PCD_SetRxFiFo HAL_PCDEx_SetRxFiFo +/** + * @} + */ + +/** @defgroup HAL_TIM_Aliased_Macros HAL TIM Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_TIM_SetICPrescalerValue TIM_SET_ICPRESCALERVALUE +#define __HAL_TIM_ResetICPrescalerValue TIM_RESET_ICPRESCALERVALUE + +#define TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE +#define TIM_GET_CLEAR_IT __HAL_TIM_CLEAR_IT + +#define __HAL_TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE + +#define __HAL_TIM_DIRECTION_STATUS __HAL_TIM_IS_TIM_COUNTING_DOWN +#define __HAL_TIM_PRESCALER __HAL_TIM_SET_PRESCALER +#define __HAL_TIM_SetCounter __HAL_TIM_SET_COUNTER +#define __HAL_TIM_GetCounter __HAL_TIM_GET_COUNTER +#define __HAL_TIM_SetAutoreload __HAL_TIM_SET_AUTORELOAD +#define __HAL_TIM_GetAutoreload __HAL_TIM_GET_AUTORELOAD +#define __HAL_TIM_SetClockDivision __HAL_TIM_SET_CLOCKDIVISION +#define __HAL_TIM_GetClockDivision __HAL_TIM_GET_CLOCKDIVISION +#define __HAL_TIM_SetICPrescaler __HAL_TIM_SET_ICPRESCALER +#define __HAL_TIM_GetICPrescaler __HAL_TIM_GET_ICPRESCALER +#define __HAL_TIM_SetCompare __HAL_TIM_SET_COMPARE +#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE + +#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1 +/** + * @} + */ + +/** @defgroup HAL_ETH_Aliased_Macros HAL ETH Aliased Macros maintained for legacy purpose + * @{ + */ + +#define __HAL_ETH_EXTI_ENABLE_IT __HAL_ETH_WAKEUP_EXTI_ENABLE_IT +#define __HAL_ETH_EXTI_DISABLE_IT __HAL_ETH_WAKEUP_EXTI_DISABLE_IT +#define __HAL_ETH_EXTI_GET_FLAG __HAL_ETH_WAKEUP_EXTI_GET_FLAG +#define __HAL_ETH_EXTI_CLEAR_FLAG __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG +#define __HAL_ETH_EXTI_SET_RISING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER +#define __HAL_ETH_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER +#define __HAL_ETH_EXTI_SET_FALLINGRISING_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER + +#define ETH_PROMISCIOUSMODE_ENABLE ETH_PROMISCUOUS_MODE_ENABLE +#define ETH_PROMISCIOUSMODE_DISABLE ETH_PROMISCUOUS_MODE_DISABLE +#define IS_ETH_PROMISCIOUS_MODE IS_ETH_PROMISCUOUS_MODE +/** + * @} + */ + +/** @defgroup HAL_LTDC_Aliased_Macros HAL LTDC Aliased Macros maintained for legacy purpose + * @{ + */ +#define __HAL_LTDC_LAYER LTDC_LAYER +#define __HAL_LTDC_RELOAD_CONFIG __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG +/** + * @} + */ + +/** @defgroup HAL_SAI_Aliased_Macros HAL SAI Aliased Macros maintained for legacy purpose + * @{ + */ +#define SAI_OUTPUTDRIVE_DISABLED SAI_OUTPUTDRIVE_DISABLE +#define SAI_OUTPUTDRIVE_ENABLED SAI_OUTPUTDRIVE_ENABLE +#define SAI_MASTERDIVIDER_ENABLED SAI_MASTERDIVIDER_ENABLE +#define SAI_MASTERDIVIDER_DISABLED SAI_MASTERDIVIDER_DISABLE +#define SAI_STREOMODE SAI_STEREOMODE +#define SAI_FIFOStatus_Empty SAI_FIFOSTATUS_EMPTY +#define SAI_FIFOStatus_Less1QuarterFull SAI_FIFOSTATUS_LESS1QUARTERFULL +#define SAI_FIFOStatus_1QuarterFull SAI_FIFOSTATUS_1QUARTERFULL +#define SAI_FIFOStatus_HalfFull SAI_FIFOSTATUS_HALFFULL +#define SAI_FIFOStatus_3QuartersFull SAI_FIFOSTATUS_3QUARTERFULL +#define SAI_FIFOStatus_Full SAI_FIFOSTATUS_FULL +#define IS_SAI_BLOCK_MONO_STREO_MODE IS_SAI_BLOCK_MONO_STEREO_MODE +#define SAI_SYNCHRONOUS_EXT SAI_SYNCHRONOUS_EXT_SAI1 +#define SAI_SYNCEXT_IN_ENABLE SAI_SYNCEXT_OUTBLOCKA_ENABLE +/** + * @} + */ + +/** @defgroup HAL_SPDIFRX_Aliased_Macros HAL SPDIFRX Aliased Macros maintained for legacy purpose + * @{ + */ +#if defined(STM32H7) +#define HAL_SPDIFRX_ReceiveControlFlow HAL_SPDIFRX_ReceiveCtrlFlow +#define HAL_SPDIFRX_ReceiveControlFlow_IT HAL_SPDIFRX_ReceiveCtrlFlow_IT +#define HAL_SPDIFRX_ReceiveControlFlow_DMA HAL_SPDIFRX_ReceiveCtrlFlow_DMA +#endif +/** + * @} + */ + +/** @defgroup HAL_HRTIM_Aliased_Functions HAL HRTIM Aliased Functions maintained for legacy purpose + * @{ + */ +#if defined (STM32H7) || defined (STM32G4) || defined (STM32F3) +#define HAL_HRTIM_WaveformCounterStart_IT HAL_HRTIM_WaveformCountStart_IT +#define HAL_HRTIM_WaveformCounterStart_DMA HAL_HRTIM_WaveformCountStart_DMA +#define HAL_HRTIM_WaveformCounterStart HAL_HRTIM_WaveformCountStart +#define HAL_HRTIM_WaveformCounterStop_IT HAL_HRTIM_WaveformCountStop_IT +#define HAL_HRTIM_WaveformCounterStop_DMA HAL_HRTIM_WaveformCountStop_DMA +#define HAL_HRTIM_WaveformCounterStop HAL_HRTIM_WaveformCountStop +#endif +/** + * @} + */ + +/** @defgroup HAL_QSPI_Aliased_Macros HAL QSPI Aliased Macros maintained for legacy purpose + * @{ + */ +#if defined (STM32L4) || defined (STM32F4) || defined (STM32F7) || defined(STM32H7) +#define HAL_QPSI_TIMEOUT_DEFAULT_VALUE HAL_QSPI_TIMEOUT_DEFAULT_VALUE +#endif /* STM32L4 || STM32F4 || STM32F7 */ +/** + * @} + */ + +/** @defgroup HAL_Generic_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose + * @{ + */ +#if defined (STM32F7) +#define ART_ACCLERATOR_ENABLE ART_ACCELERATOR_ENABLE +#endif /* STM32F7 */ +/** + * @} + */ + +/** @defgroup HAL_PPP_Aliased_Macros HAL PPP Aliased Macros maintained for legacy purpose + * @{ + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32_HAL_LEGACY */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h index f7eb847..5d8cdd3 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h @@ -1,297 +1,297 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal.h - * @author MCD Application Team - * @brief This file contains all the functions prototypes for the HAL - * module driver. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_H -#define __STM32F4xx_HAL_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_conf.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HAL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_Exported_Constants HAL Exported Constants - * @{ - */ - -/** @defgroup HAL_TICK_FREQ Tick Frequency - * @{ - */ -typedef enum -{ - HAL_TICK_FREQ_10HZ = 100U, - HAL_TICK_FREQ_100HZ = 10U, - HAL_TICK_FREQ_1KHZ = 1U, - HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ -} HAL_TickFreqTypeDef; -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup HAL_Exported_Macros HAL Exported Macros - * @{ - */ - -/** @brief Freeze/Unfreeze Peripherals in Debug mode - */ -#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM4() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM5() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM12() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM13() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_CAN1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_FREEZE_CAN2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM8() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM9() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM10() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM11() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM4() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM5() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM12() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM13() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_CAN1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_CAN2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM8() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM9() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM10() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM11() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -/** @brief Main Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FLASH() (SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE)) - -/** @brief System Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= SYSCFG_MEMRMP_MEM_MODE_0;\ - }while(0); - -/** @brief Embedded SRAM mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_0 | SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @brief FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FSMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief FMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -/** @brief FMC/SDRAM Bank 1 and 2 mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_2);\ - }while(0); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup Cortex_Lockup_Enable Cortex Lockup Enable - * @{ - */ -/** @brief SYSCFG Break Lockup lock - * Enables and locks the connection of Cortex-M4 LOCKUP (Hardfault) output to TIM1/8 input - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_PVD_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_PVD_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_PVD_LOCK; \ - }while(0) -/** - * @} - */ - -/** @defgroup PVD_Lock_Enable PVD Lock - * @{ - */ -/** @brief SYSCFG Break PVD lock - * Enables and locks the PVD connection with Timer1/8 Break Input, , as well as the PVDE and PLS[2:0] in the PWR_CR register - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_LOCKUP_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_LOCKUP_LOCK; \ - }while(0) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup HAL_Private_Macros HAL Private Macros - * @{ - */ -#define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \ - ((FREQ) == HAL_TICK_FREQ_100HZ) || \ - ((FREQ) == HAL_TICK_FREQ_1KHZ)) -/** - * @} - */ - -/* Exported variables --------------------------------------------------------*/ - -/** @addtogroup HAL_Exported_Variables - * @{ - */ -extern __IO uint32_t uwTick; -extern uint32_t uwTickPrio; -extern HAL_TickFreqTypeDef uwTickFreq; -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup HAL_Exported_Functions - * @{ - */ -/** @addtogroup HAL_Exported_Functions_Group1 - * @{ - */ -/* Initialization and Configuration functions ******************************/ -HAL_StatusTypeDef HAL_Init(void); -HAL_StatusTypeDef HAL_DeInit(void); -void HAL_MspInit(void); -void HAL_MspDeInit(void); -HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority); -/** - * @} - */ - -/** @addtogroup HAL_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_IncTick(void); -void HAL_Delay(uint32_t Delay); -uint32_t HAL_GetTick(void); -uint32_t HAL_GetTickPrio(void); -HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq); -HAL_TickFreqTypeDef HAL_GetTickFreq(void); -void HAL_SuspendTick(void); -void HAL_ResumeTick(void); -uint32_t HAL_GetHalVersion(void); -uint32_t HAL_GetREVID(void); -uint32_t HAL_GetDEVID(void); -void HAL_DBGMCU_EnableDBGSleepMode(void); -void HAL_DBGMCU_DisableDBGSleepMode(void); -void HAL_DBGMCU_EnableDBGStopMode(void); -void HAL_DBGMCU_DisableDBGStopMode(void); -void HAL_DBGMCU_EnableDBGStandbyMode(void); -void HAL_DBGMCU_DisableDBGStandbyMode(void); -void HAL_EnableCompensationCell(void); -void HAL_DisableCompensationCell(void); -uint32_t HAL_GetUIDw0(void); -uint32_t HAL_GetUIDw1(void); -uint32_t HAL_GetUIDw2(void); -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -void HAL_EnableMemorySwappingBank(void); -void HAL_DisableMemorySwappingBank(void); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Variables HAL Private Variables - * @{ - */ -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Constants HAL Private Constants - * @{ - */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_H */ - - +/** + ****************************************************************************** + * @file stm32f4xx_hal.h + * @author MCD Application Team + * @brief This file contains all the functions prototypes for the HAL + * module driver. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_H +#define __STM32F4xx_HAL_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_conf.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup HAL + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup HAL_Exported_Constants HAL Exported Constants + * @{ + */ + +/** @defgroup HAL_TICK_FREQ Tick Frequency + * @{ + */ +typedef enum +{ + HAL_TICK_FREQ_10HZ = 100U, + HAL_TICK_FREQ_100HZ = 10U, + HAL_TICK_FREQ_1KHZ = 1U, + HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ +} HAL_TickFreqTypeDef; +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup HAL_Exported_Macros HAL Exported Macros + * @{ + */ + +/** @brief Freeze/Unfreeze Peripherals in Debug mode + */ +#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM4() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM4_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM5() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM5_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM12() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM12_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM13() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM13_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP)) +#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP)) +#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP)) +#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP)) +#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_CAN1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN1_STOP)) +#define __HAL_DBGMCU_FREEZE_CAN2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN2_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM8() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM8_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM9() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM9_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM10() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM10_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM11() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM11_STOP)) + +#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM4() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM4_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM5() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM5_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM12() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM12_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM13() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM13_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP)) +#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP)) +#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP)) +#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP)) +#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_CAN1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN1_STOP)) +#define __HAL_DBGMCU_UNFREEZE_CAN2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN2_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM8() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM8_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM9() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM9_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM10() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM10_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM11() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM11_STOP)) + +/** @brief Main Flash memory mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FLASH() (SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE)) + +/** @brief System Flash memory mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ + SYSCFG->MEMRMP |= SYSCFG_MEMRMP_MEM_MODE_0;\ + }while(0); + +/** @brief Embedded SRAM mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_SRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ + SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_0 | SYSCFG_MEMRMP_MEM_MODE_1);\ + }while(0); + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) +/** @brief FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FSMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ + SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ + }while(0); +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +/** @brief FMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ + SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ + }while(0); + +/** @brief FMC/SDRAM Bank 1 and 2 mapped at 0x00000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ + SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_2);\ + }while(0); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup Cortex_Lockup_Enable Cortex Lockup Enable + * @{ + */ +/** @brief SYSCFG Break Lockup lock + * Enables and locks the connection of Cortex-M4 LOCKUP (Hardfault) output to TIM1/8 input + * @note The selected configuration is locked and can be unlocked by system reset + */ +#define __HAL_SYSCFG_BREAK_PVD_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_PVD_LOCK); \ + SYSCFG->CFGR2 |= SYSCFG_CFGR2_PVD_LOCK; \ + }while(0) +/** + * @} + */ + +/** @defgroup PVD_Lock_Enable PVD Lock + * @{ + */ +/** @brief SYSCFG Break PVD lock + * Enables and locks the PVD connection with Timer1/8 Break Input, , as well as the PVDE and PLS[2:0] in the PWR_CR register + * @note The selected configuration is locked and can be unlocked by system reset + */ +#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_LOCKUP_LOCK); \ + SYSCFG->CFGR2 |= SYSCFG_CFGR2_LOCKUP_LOCK; \ + }while(0) +/** + * @} + */ +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx || STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup HAL_Private_Macros HAL Private Macros + * @{ + */ +#define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \ + ((FREQ) == HAL_TICK_FREQ_100HZ) || \ + ((FREQ) == HAL_TICK_FREQ_1KHZ)) +/** + * @} + */ + +/* Exported variables --------------------------------------------------------*/ + +/** @addtogroup HAL_Exported_Variables + * @{ + */ +extern __IO uint32_t uwTick; +extern uint32_t uwTickPrio; +extern HAL_TickFreqTypeDef uwTickFreq; +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup HAL_Exported_Functions + * @{ + */ +/** @addtogroup HAL_Exported_Functions_Group1 + * @{ + */ +/* Initialization and Configuration functions ******************************/ +HAL_StatusTypeDef HAL_Init(void); +HAL_StatusTypeDef HAL_DeInit(void); +void HAL_MspInit(void); +void HAL_MspDeInit(void); +HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority); +/** + * @} + */ + +/** @addtogroup HAL_Exported_Functions_Group2 + * @{ + */ +/* Peripheral Control functions ************************************************/ +void HAL_IncTick(void); +void HAL_Delay(uint32_t Delay); +uint32_t HAL_GetTick(void); +uint32_t HAL_GetTickPrio(void); +HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq); +HAL_TickFreqTypeDef HAL_GetTickFreq(void); +void HAL_SuspendTick(void); +void HAL_ResumeTick(void); +uint32_t HAL_GetHalVersion(void); +uint32_t HAL_GetREVID(void); +uint32_t HAL_GetDEVID(void); +void HAL_DBGMCU_EnableDBGSleepMode(void); +void HAL_DBGMCU_DisableDBGSleepMode(void); +void HAL_DBGMCU_EnableDBGStopMode(void); +void HAL_DBGMCU_DisableDBGStopMode(void); +void HAL_DBGMCU_EnableDBGStandbyMode(void); +void HAL_DBGMCU_DisableDBGStandbyMode(void); +void HAL_EnableCompensationCell(void); +void HAL_DisableCompensationCell(void); +uint32_t HAL_GetUIDw0(void); +uint32_t HAL_GetUIDw1(void); +uint32_t HAL_GetUIDw2(void); +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +void HAL_EnableMemorySwappingBank(void); +void HAL_DisableMemorySwappingBank(void); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup HAL_Private_Variables HAL Private Variables + * @{ + */ +/** + * @} + */ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup HAL_Private_Constants HAL Private Constants + * @{ + */ +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h new file mode 100644 index 0000000..af04f8b --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h @@ -0,0 +1,898 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc.h + * @author MCD Application Team + * @brief Header file containing functions prototypes of ADC HAL library. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_ADC_H +#define __STM32F4xx_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/* Include low level driver */ +#include "stm32f4xx_ll_adc.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup ADC_Exported_Types ADC Exported Types + * @{ + */ + +/** + * @brief Structure definition of ADC and regular group initialization + * @note Parameters of this structure are shared within 2 scopes: + * - Scope entire ADC (affects regular and injected groups): ClockPrescaler, Resolution, ScanConvMode, DataAlign, ScanConvMode, EOCSelection, LowPowerAutoWait, LowPowerAutoPowerOff, ChannelsBank. + * - Scope regular group: ContinuousConvMode, NbrOfConversion, DiscontinuousConvMode, NbrOfDiscConversion, ExternalTrigConvEdge, ExternalTrigConv. + * @note The setting of these parameters with function HAL_ADC_Init() is conditioned to ADC state. + * ADC state can be either: + * - For all parameters: ADC disabled + * - For all parameters except 'Resolution', 'ScanConvMode', 'DiscontinuousConvMode', 'NbrOfDiscConversion' : ADC enabled without conversion on going on regular group. + * - For parameters 'ExternalTrigConv' and 'ExternalTrigConvEdge': ADC enabled, even with conversion on going. + * If ADC is not in the appropriate state to modify some parameters, these parameters setting is bypassed + * without error reporting (as it can be the expected behaviour in case of intended action to update another parameter (which fulfills the ADC state condition) on the fly). + */ +typedef struct +{ + uint32_t ClockPrescaler; /*!< Select ADC clock prescaler. The clock is common for + all the ADCs. + This parameter can be a value of @ref ADC_ClockPrescaler */ + uint32_t Resolution; /*!< Configures the ADC resolution. + This parameter can be a value of @ref ADC_Resolution */ + uint32_t DataAlign; /*!< Specifies ADC data alignment to right (MSB on register bit 11 and LSB on register bit 0) (default setting) + or to left (if regular group: MSB on register bit 15 and LSB on register bit 4, if injected group (MSB kept as signed value due to potential negative value after offset application): MSB on register bit 14 and LSB on register bit 3). + This parameter can be a value of @ref ADC_Data_align */ + uint32_t ScanConvMode; /*!< Configures the sequencer of regular and injected groups. + This parameter can be associated to parameter 'DiscontinuousConvMode' to have main sequence subdivided in successive parts. + If disabled: Conversion is performed in single mode (one channel converted, the one defined in rank 1). + Parameters 'NbrOfConversion' and 'InjectedNbrOfConversion' are discarded (equivalent to set to 1). + If enabled: Conversions are performed in sequence mode (multiple ranks defined by 'NbrOfConversion'/'InjectedNbrOfConversion' and each channel rank). + Scan direction is upward: from rank1 to rank 'n'. + This parameter can be set to ENABLE or DISABLE */ + uint32_t EOCSelection; /*!< Specifies what EOC (End Of Conversion) flag is used for conversion by polling and interruption: end of conversion of each rank or complete sequence. + This parameter can be a value of @ref ADC_EOCSelection. + Note: For injected group, end of conversion (flag&IT) is raised only at the end of the sequence. + Therefore, if end of conversion is set to end of each conversion, injected group should not be used with interruption (HAL_ADCEx_InjectedStart_IT) + or polling (HAL_ADCEx_InjectedStart and HAL_ADCEx_InjectedPollForConversion). By the way, polling is still possible since driver will use an estimated timing for end of injected conversion. + Note: If overrun feature is intended to be used, use ADC in mode 'interruption' (function HAL_ADC_Start_IT() ) with parameter EOCSelection set to end of each conversion or in mode 'transfer by DMA' (function HAL_ADC_Start_DMA()). + If overrun feature is intended to be bypassed, use ADC in mode 'polling' or 'interruption' with parameter EOCSelection must be set to end of sequence */ + FunctionalState ContinuousConvMode; /*!< Specifies whether the conversion is performed in single mode (one conversion) or continuous mode for regular group, + after the selected trigger occurred (software start or external trigger). + This parameter can be set to ENABLE or DISABLE. */ + uint32_t NbrOfConversion; /*!< Specifies the number of ranks that will be converted within the regular group sequencer. + To use regular group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. + This parameter must be a number between Min_Data = 1 and Max_Data = 16. */ + FunctionalState DiscontinuousConvMode; /*!< Specifies whether the conversions sequence of regular group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). + Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. + Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. + This parameter can be set to ENABLE or DISABLE. */ + uint32_t NbrOfDiscConversion; /*!< Specifies the number of discontinuous conversions in which the main sequence of regular group (parameter NbrOfConversion) will be subdivided. + If parameter 'DiscontinuousConvMode' is disabled, this parameter is discarded. + This parameter must be a number between Min_Data = 1 and Max_Data = 8. */ + uint32_t ExternalTrigConv; /*!< Selects the external event used to trigger the conversion start of regular group. + If set to ADC_SOFTWARE_START, external triggers are disabled. + If set to external trigger source, triggering is on event rising edge by default. + This parameter can be a value of @ref ADC_External_trigger_Source_Regular */ + uint32_t ExternalTrigConvEdge; /*!< Selects the external trigger edge of regular group. + If trigger is set to ADC_SOFTWARE_START, this parameter is discarded. + This parameter can be a value of @ref ADC_External_trigger_edge_Regular */ + FunctionalState DMAContinuousRequests; /*!< Specifies whether the DMA requests are performed in one shot mode (DMA transfer stop when number of conversions is reached) + or in Continuous mode (DMA transfer unlimited, whatever number of conversions). + Note: In continuous mode, DMA must be configured in circular mode. Otherwise an overrun will be triggered when DMA buffer maximum pointer is reached. + Note: This parameter must be modified when no conversion is on going on both regular and injected groups (ADC disabled, or ADC enabled without continuous mode or external trigger that could launch a conversion). + This parameter can be set to ENABLE or DISABLE. */ +}ADC_InitTypeDef; + + + +/** + * @brief Structure definition of ADC channel for regular group + * @note The setting of these parameters with function HAL_ADC_ConfigChannel() is conditioned to ADC state. + * ADC can be either disabled or enabled without conversion on going on regular group. + */ +typedef struct +{ + uint32_t Channel; /*!< Specifies the channel to configure into ADC regular group. + This parameter can be a value of @ref ADC_channels */ + uint32_t Rank; /*!< Specifies the rank in the regular group sequencer. + This parameter must be a number between Min_Data = 1 and Max_Data = 16 */ + uint32_t SamplingTime; /*!< Sampling time value to be set for the selected channel. + Unit: ADC clock cycles + Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). + This parameter can be a value of @ref ADC_sampling_times + Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. + If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. + Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), + sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) + Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ + uint32_t Offset; /*!< Reserved for future use, can be set to 0 */ +}ADC_ChannelConfTypeDef; + +/** + * @brief ADC Configuration multi-mode structure definition + */ +typedef struct +{ + uint32_t WatchdogMode; /*!< Configures the ADC analog watchdog mode. + This parameter can be a value of @ref ADC_analog_watchdog_selection */ + uint32_t HighThreshold; /*!< Configures the ADC analog watchdog High threshold value. + This parameter must be a 12-bit value. */ + uint32_t LowThreshold; /*!< Configures the ADC analog watchdog High threshold value. + This parameter must be a 12-bit value. */ + uint32_t Channel; /*!< Configures ADC channel for the analog watchdog. + This parameter has an effect only if watchdog mode is configured on single channel + This parameter can be a value of @ref ADC_channels */ + FunctionalState ITMode; /*!< Specifies whether the analog watchdog is configured + is interrupt mode or in polling mode. + This parameter can be set to ENABLE or DISABLE */ + uint32_t WatchdogNumber; /*!< Reserved for future use, can be set to 0 */ +}ADC_AnalogWDGConfTypeDef; + +/** + * @brief HAL ADC state machine: ADC states definition (bitfields) + */ +/* States of ADC global scope */ +#define HAL_ADC_STATE_RESET 0x00000000U /*!< ADC not yet initialized or disabled */ +#define HAL_ADC_STATE_READY 0x00000001U /*!< ADC peripheral ready for use */ +#define HAL_ADC_STATE_BUSY_INTERNAL 0x00000002U /*!< ADC is busy to internal process (initialization, calibration) */ +#define HAL_ADC_STATE_TIMEOUT 0x00000004U /*!< TimeOut occurrence */ + +/* States of ADC errors */ +#define HAL_ADC_STATE_ERROR_INTERNAL 0x00000010U /*!< Internal error occurrence */ +#define HAL_ADC_STATE_ERROR_CONFIG 0x00000020U /*!< Configuration error occurrence */ +#define HAL_ADC_STATE_ERROR_DMA 0x00000040U /*!< DMA error occurrence */ + +/* States of ADC group regular */ +#define HAL_ADC_STATE_REG_BUSY 0x00000100U /*!< A conversion on group regular is ongoing or can occur (either by continuous mode, + external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ +#define HAL_ADC_STATE_REG_EOC 0x00000200U /*!< Conversion data available on group regular */ +#define HAL_ADC_STATE_REG_OVR 0x00000400U /*!< Overrun occurrence */ + +/* States of ADC group injected */ +#define HAL_ADC_STATE_INJ_BUSY 0x00001000U /*!< A conversion on group injected is ongoing or can occur (either by auto-injection mode, + external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ +#define HAL_ADC_STATE_INJ_EOC 0x00002000U /*!< Conversion data available on group injected */ + +/* States of ADC analog watchdogs */ +#define HAL_ADC_STATE_AWD1 0x00010000U /*!< Out-of-window occurrence of analog watchdog 1 */ +#define HAL_ADC_STATE_AWD2 0x00020000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 2 */ +#define HAL_ADC_STATE_AWD3 0x00040000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 3 */ + +/* States of ADC multi-mode */ +#define HAL_ADC_STATE_MULTIMODE_SLAVE 0x00100000U /*!< Not available on STM32F4 device: ADC in multimode slave state, controlled by another ADC master ( */ + + +/** + * @brief ADC handle Structure definition + */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +typedef struct __ADC_HandleTypeDef +#else +typedef struct +#endif +{ + ADC_TypeDef *Instance; /*!< Register base address */ + + ADC_InitTypeDef Init; /*!< ADC required parameters */ + + __IO uint32_t NbrOfCurrentConversionRank; /*!< ADC number of current conversion rank */ + + DMA_HandleTypeDef *DMA_Handle; /*!< Pointer DMA Handler */ + + HAL_LockTypeDef Lock; /*!< ADC locking object */ + + __IO uint32_t State; /*!< ADC communication state */ + + __IO uint32_t ErrorCode; /*!< ADC Error code */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + void (* ConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion complete callback */ + void (* ConvHalfCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion DMA half-transfer callback */ + void (* LevelOutOfWindowCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC analog watchdog 1 callback */ + void (* ErrorCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC error callback */ + void (* InjectedConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC group injected conversion complete callback */ + void (* MspInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp Init callback */ + void (* MspDeInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp DeInit callback */ +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +}ADC_HandleTypeDef; + +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +/** + * @brief HAL ADC Callback ID enumeration definition + */ +typedef enum +{ + HAL_ADC_CONVERSION_COMPLETE_CB_ID = 0x00U, /*!< ADC conversion complete callback ID */ + HAL_ADC_CONVERSION_HALF_CB_ID = 0x01U, /*!< ADC conversion DMA half-transfer callback ID */ + HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID = 0x02U, /*!< ADC analog watchdog 1 callback ID */ + HAL_ADC_ERROR_CB_ID = 0x03U, /*!< ADC error callback ID */ + HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID = 0x04U, /*!< ADC group injected conversion complete callback ID */ + HAL_ADC_MSPINIT_CB_ID = 0x05U, /*!< ADC Msp Init callback ID */ + HAL_ADC_MSPDEINIT_CB_ID = 0x06U /*!< ADC Msp DeInit callback ID */ +} HAL_ADC_CallbackIDTypeDef; + +/** + * @brief HAL ADC Callback pointer definition + */ +typedef void (*pADC_CallbackTypeDef)(ADC_HandleTypeDef *hadc); /*!< pointer to a ADC callback function */ + +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup ADC_Exported_Constants ADC Exported Constants + * @{ + */ + +/** @defgroup ADC_Error_Code ADC Error Code + * @{ + */ +#define HAL_ADC_ERROR_NONE 0x00U /*!< No error */ +#define HAL_ADC_ERROR_INTERNAL 0x01U /*!< ADC IP internal error: if problem of clocking, + enable/disable, erroneous state */ +#define HAL_ADC_ERROR_OVR 0x02U /*!< Overrun error */ +#define HAL_ADC_ERROR_DMA 0x04U /*!< DMA transfer error */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +#define HAL_ADC_ERROR_INVALID_CALLBACK (0x10U) /*!< Invalid Callback error */ +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +/** + * @} + */ + + +/** @defgroup ADC_ClockPrescaler ADC Clock Prescaler + * @{ + */ +#define ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000U +#define ADC_CLOCK_SYNC_PCLK_DIV4 ((uint32_t)ADC_CCR_ADCPRE_0) +#define ADC_CLOCK_SYNC_PCLK_DIV6 ((uint32_t)ADC_CCR_ADCPRE_1) +#define ADC_CLOCK_SYNC_PCLK_DIV8 ((uint32_t)ADC_CCR_ADCPRE) +/** + * @} + */ + +/** @defgroup ADC_delay_between_2_sampling_phases ADC Delay Between 2 Sampling Phases + * @{ + */ +#define ADC_TWOSAMPLINGDELAY_5CYCLES 0x00000000U +#define ADC_TWOSAMPLINGDELAY_6CYCLES ((uint32_t)ADC_CCR_DELAY_0) +#define ADC_TWOSAMPLINGDELAY_7CYCLES ((uint32_t)ADC_CCR_DELAY_1) +#define ADC_TWOSAMPLINGDELAY_8CYCLES ((uint32_t)(ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_9CYCLES ((uint32_t)ADC_CCR_DELAY_2) +#define ADC_TWOSAMPLINGDELAY_10CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_11CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) +#define ADC_TWOSAMPLINGDELAY_12CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_13CYCLES ((uint32_t)ADC_CCR_DELAY_3) +#define ADC_TWOSAMPLINGDELAY_14CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_15CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1)) +#define ADC_TWOSAMPLINGDELAY_16CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_17CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2)) +#define ADC_TWOSAMPLINGDELAY_18CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) +#define ADC_TWOSAMPLINGDELAY_19CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) +#define ADC_TWOSAMPLINGDELAY_20CYCLES ((uint32_t)ADC_CCR_DELAY) +/** + * @} + */ + +/** @defgroup ADC_Resolution ADC Resolution + * @{ + */ +#define ADC_RESOLUTION_12B 0x00000000U +#define ADC_RESOLUTION_10B ((uint32_t)ADC_CR1_RES_0) +#define ADC_RESOLUTION_8B ((uint32_t)ADC_CR1_RES_1) +#define ADC_RESOLUTION_6B ((uint32_t)ADC_CR1_RES) +/** + * @} + */ + +/** @defgroup ADC_External_trigger_edge_Regular ADC External Trigger Edge Regular + * @{ + */ +#define ADC_EXTERNALTRIGCONVEDGE_NONE 0x00000000U +#define ADC_EXTERNALTRIGCONVEDGE_RISING ((uint32_t)ADC_CR2_EXTEN_0) +#define ADC_EXTERNALTRIGCONVEDGE_FALLING ((uint32_t)ADC_CR2_EXTEN_1) +#define ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_EXTEN) +/** + * @} + */ + +/** @defgroup ADC_External_trigger_Source_Regular ADC External Trigger Source Regular + * @{ + */ +/* Note: Parameter ADC_SOFTWARE_START is a software parameter used for */ +/* compatibility with other STM32 devices. */ +#define ADC_EXTERNALTRIGCONV_T1_CC1 0x00000000U +#define ADC_EXTERNALTRIGCONV_T1_CC2 ((uint32_t)ADC_CR2_EXTSEL_0) +#define ADC_EXTERNALTRIGCONV_T1_CC3 ((uint32_t)ADC_CR2_EXTSEL_1) +#define ADC_EXTERNALTRIGCONV_T2_CC2 ((uint32_t)(ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T2_CC3 ((uint32_t)ADC_CR2_EXTSEL_2) +#define ADC_EXTERNALTRIGCONV_T2_CC4 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T2_TRGO ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) +#define ADC_EXTERNALTRIGCONV_T3_CC1 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T3_TRGO ((uint32_t)ADC_CR2_EXTSEL_3) +#define ADC_EXTERNALTRIGCONV_T4_CC4 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T5_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1)) +#define ADC_EXTERNALTRIGCONV_T5_CC2 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T5_CC3 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2)) +#define ADC_EXTERNALTRIGCONV_T8_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) +#define ADC_EXTERNALTRIGCONV_T8_TRGO ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) +#define ADC_EXTERNALTRIGCONV_Ext_IT11 ((uint32_t)ADC_CR2_EXTSEL) +#define ADC_SOFTWARE_START ((uint32_t)ADC_CR2_EXTSEL + 1U) +/** + * @} + */ + +/** @defgroup ADC_Data_align ADC Data Align + * @{ + */ +#define ADC_DATAALIGN_RIGHT 0x00000000U +#define ADC_DATAALIGN_LEFT ((uint32_t)ADC_CR2_ALIGN) +/** + * @} + */ + +/** @defgroup ADC_channels ADC Common Channels + * @{ + */ +#define ADC_CHANNEL_0 0x00000000U +#define ADC_CHANNEL_1 ((uint32_t)ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_2 ((uint32_t)ADC_CR1_AWDCH_1) +#define ADC_CHANNEL_3 ((uint32_t)(ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_4 ((uint32_t)ADC_CR1_AWDCH_2) +#define ADC_CHANNEL_5 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_6 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) +#define ADC_CHANNEL_7 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_8 ((uint32_t)ADC_CR1_AWDCH_3) +#define ADC_CHANNEL_9 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_10 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1)) +#define ADC_CHANNEL_11 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_12 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2)) +#define ADC_CHANNEL_13 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_14 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) +#define ADC_CHANNEL_15 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_16 ((uint32_t)ADC_CR1_AWDCH_4) +#define ADC_CHANNEL_17 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0)) +#define ADC_CHANNEL_18 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1)) + +#define ADC_CHANNEL_VREFINT ((uint32_t)ADC_CHANNEL_17) +#define ADC_CHANNEL_VBAT ((uint32_t)ADC_CHANNEL_18) +/** + * @} + */ + +/** @defgroup ADC_sampling_times ADC Sampling Times + * @{ + */ +#define ADC_SAMPLETIME_3CYCLES 0x00000000U +#define ADC_SAMPLETIME_15CYCLES ((uint32_t)ADC_SMPR1_SMP10_0) +#define ADC_SAMPLETIME_28CYCLES ((uint32_t)ADC_SMPR1_SMP10_1) +#define ADC_SAMPLETIME_56CYCLES ((uint32_t)(ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0)) +#define ADC_SAMPLETIME_84CYCLES ((uint32_t)ADC_SMPR1_SMP10_2) +#define ADC_SAMPLETIME_112CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0)) +#define ADC_SAMPLETIME_144CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1)) +#define ADC_SAMPLETIME_480CYCLES ((uint32_t)ADC_SMPR1_SMP10) +/** + * @} + */ + + /** @defgroup ADC_EOCSelection ADC EOC Selection + * @{ + */ +#define ADC_EOC_SEQ_CONV 0x00000000U +#define ADC_EOC_SINGLE_CONV 0x00000001U +#define ADC_EOC_SINGLE_SEQ_CONV 0x00000002U /*!< reserved for future use */ +/** + * @} + */ + +/** @defgroup ADC_Event_type ADC Event Type + * @{ + */ +#define ADC_AWD_EVENT ((uint32_t)ADC_FLAG_AWD) +#define ADC_OVR_EVENT ((uint32_t)ADC_FLAG_OVR) +/** + * @} + */ + +/** @defgroup ADC_analog_watchdog_selection ADC Analog Watchdog Selection + * @{ + */ +#define ADC_ANALOGWATCHDOG_SINGLE_REG ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN)) +#define ADC_ANALOGWATCHDOG_SINGLE_INJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN)) +#define ADC_ANALOGWATCHDOG_SINGLE_REGINJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) +#define ADC_ANALOGWATCHDOG_ALL_REG ((uint32_t)ADC_CR1_AWDEN) +#define ADC_ANALOGWATCHDOG_ALL_INJEC ((uint32_t)ADC_CR1_JAWDEN) +#define ADC_ANALOGWATCHDOG_ALL_REGINJEC ((uint32_t)(ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) +#define ADC_ANALOGWATCHDOG_NONE 0x00000000U +/** + * @} + */ + +/** @defgroup ADC_interrupts_definition ADC Interrupts Definition + * @{ + */ +#define ADC_IT_EOC ((uint32_t)ADC_CR1_EOCIE) +#define ADC_IT_AWD ((uint32_t)ADC_CR1_AWDIE) +#define ADC_IT_JEOC ((uint32_t)ADC_CR1_JEOCIE) +#define ADC_IT_OVR ((uint32_t)ADC_CR1_OVRIE) +/** + * @} + */ + +/** @defgroup ADC_flags_definition ADC Flags Definition + * @{ + */ +#define ADC_FLAG_AWD ((uint32_t)ADC_SR_AWD) +#define ADC_FLAG_EOC ((uint32_t)ADC_SR_EOC) +#define ADC_FLAG_JEOC ((uint32_t)ADC_SR_JEOC) +#define ADC_FLAG_JSTRT ((uint32_t)ADC_SR_JSTRT) +#define ADC_FLAG_STRT ((uint32_t)ADC_SR_STRT) +#define ADC_FLAG_OVR ((uint32_t)ADC_SR_OVR) +/** + * @} + */ + +/** @defgroup ADC_channels_type ADC Channels Type + * @{ + */ +#define ADC_ALL_CHANNELS 0x00000001U +#define ADC_REGULAR_CHANNELS 0x00000002U /*!< reserved for future use */ +#define ADC_INJECTED_CHANNELS 0x00000003U /*!< reserved for future use */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup ADC_Exported_Macros ADC Exported Macros + * @{ + */ + +/** @brief Reset ADC handle state + * @param __HANDLE__ ADC handle + * @retval None + */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ + do{ \ + (__HANDLE__)->State = HAL_ADC_STATE_RESET; \ + (__HANDLE__)->MspInitCallback = NULL; \ + (__HANDLE__)->MspDeInitCallback = NULL; \ + } while(0) +#else +#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ + ((__HANDLE__)->State = HAL_ADC_STATE_RESET) +#endif + +/** + * @brief Enable the ADC peripheral. + * @param __HANDLE__ ADC handle + * @retval None + */ +#define __HAL_ADC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 |= ADC_CR2_ADON) + +/** + * @brief Disable the ADC peripheral. + * @param __HANDLE__ ADC handle + * @retval None + */ +#define __HAL_ADC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= ~ADC_CR2_ADON) + +/** + * @brief Enable the ADC end of conversion interrupt. + * @param __HANDLE__ specifies the ADC Handle. + * @param __INTERRUPT__ ADC Interrupt. + * @retval None + */ +#define __HAL_ADC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) |= (__INTERRUPT__)) + +/** + * @brief Disable the ADC end of conversion interrupt. + * @param __HANDLE__ specifies the ADC Handle. + * @param __INTERRUPT__ ADC interrupt. + * @retval None + */ +#define __HAL_ADC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) &= ~(__INTERRUPT__)) + +/** @brief Check if the specified ADC interrupt source is enabled or disabled. + * @param __HANDLE__ specifies the ADC Handle. + * @param __INTERRUPT__ specifies the ADC interrupt source to check. + * @retval The new state of __IT__ (TRUE or FALSE). + */ +#define __HAL_ADC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) + +/** + * @brief Clear the ADC's pending flags. + * @param __HANDLE__ specifies the ADC Handle. + * @param __FLAG__ ADC flag. + * @retval None + */ +#define __HAL_ADC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = ~(__FLAG__)) + +/** + * @brief Get the selected ADC's flag status. + * @param __HANDLE__ specifies the ADC Handle. + * @param __FLAG__ ADC flag. + * @retval None + */ +#define __HAL_ADC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) + +/** + * @} + */ + +/* Include ADC HAL Extension module */ +#include "stm32f4xx_hal_adc_ex.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup ADC_Exported_Functions + * @{ + */ + +/** @addtogroup ADC_Exported_Functions_Group1 + * @{ + */ +/* Initialization/de-initialization functions ***********************************/ +HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc); +void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc); +void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc); + +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +/* Callbacks Register/UnRegister functions ***********************************/ +HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @addtogroup ADC_Exported_Functions_Group2 + * @{ + */ +/* I/O operation functions ******************************************************/ +HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); + +HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout); + +HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc); + +void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc); + +HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); +HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc); + +uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc); + +void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc); +void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc); +void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc); +void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc); +/** + * @} + */ + +/** @addtogroup ADC_Exported_Functions_Group3 + * @{ + */ +/* Peripheral Control functions *************************************************/ +HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig); +HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig); +/** + * @} + */ + +/** @addtogroup ADC_Exported_Functions_Group4 + * @{ + */ +/* Peripheral State functions ***************************************************/ +uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc); +uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc); +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup ADC_Private_Constants ADC Private Constants + * @{ + */ +/* Delay for ADC stabilization time. */ +/* Maximum delay is 1us (refer to device datasheet, parameter tSTAB). */ +/* Unit: us */ +#define ADC_STAB_DELAY_US 3U +/* Delay for temperature sensor stabilization time. */ +/* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */ +/* Unit: us */ +#define ADC_TEMPSENSOR_DELAY_US 10U +/** + * @} + */ + +/* Private macro ------------------------------------------------------------*/ + +/** @defgroup ADC_Private_Macros ADC Private Macros + * @{ + */ +/* Macro reserved for internal HAL driver usage, not intended to be used in + code of final user */ + +/** + * @brief Verification of ADC state: enabled or disabled + * @param __HANDLE__ ADC handle + * @retval SET (ADC enabled) or RESET (ADC disabled) + */ +#define ADC_IS_ENABLE(__HANDLE__) \ + ((( ((__HANDLE__)->Instance->SR & ADC_SR_ADONS) == ADC_SR_ADONS ) \ + ) ? SET : RESET) + +/** + * @brief Test if conversion trigger of regular group is software start + * or external trigger. + * @param __HANDLE__ ADC handle + * @retval SET (software start) or RESET (external trigger) + */ +#define ADC_IS_SOFTWARE_START_REGULAR(__HANDLE__) \ + (((__HANDLE__)->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + +/** + * @brief Test if conversion trigger of injected group is software start + * or external trigger. + * @param __HANDLE__ ADC handle + * @retval SET (software start) or RESET (external trigger) + */ +#define ADC_IS_SOFTWARE_START_INJECTED(__HANDLE__) \ + (((__HANDLE__)->Instance->CR2 & ADC_CR2_JEXTEN) == RESET) + +/** + * @brief Simultaneously clears and sets specific bits of the handle State + * @note: ADC_STATE_CLR_SET() macro is merely aliased to generic macro MODIFY_REG(), + * the first parameter is the ADC handle State, the second parameter is the + * bit field to clear, the third and last parameter is the bit field to set. + * @retval None + */ +#define ADC_STATE_CLR_SET MODIFY_REG + +/** + * @brief Clear ADC error code (set it to error code: "no error") + * @param __HANDLE__ ADC handle + * @retval None + */ +#define ADC_CLEAR_ERRORCODE(__HANDLE__) \ + ((__HANDLE__)->ErrorCode = HAL_ADC_ERROR_NONE) + + +#define IS_ADC_CLOCKPRESCALER(ADC_CLOCK) (((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV2) || \ + ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV4) || \ + ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV6) || \ + ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV8)) +#define IS_ADC_SAMPLING_DELAY(DELAY) (((DELAY) == ADC_TWOSAMPLINGDELAY_5CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_6CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_7CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_8CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_9CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_10CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_11CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_12CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_13CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_14CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_15CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_16CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_17CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_18CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_19CYCLES) || \ + ((DELAY) == ADC_TWOSAMPLINGDELAY_20CYCLES)) +#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_RESOLUTION_12B) || \ + ((RESOLUTION) == ADC_RESOLUTION_10B) || \ + ((RESOLUTION) == ADC_RESOLUTION_8B) || \ + ((RESOLUTION) == ADC_RESOLUTION_6B)) +#define IS_ADC_EXT_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGCONVEDGE_NONE) || \ + ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISING) || \ + ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_FALLING) || \ + ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING)) +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC1) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC2) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC3) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC2) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC3) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC4) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_TRGO) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_CC1) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_TRGO) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T4_CC4) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC1) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC2) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC3) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_CC1) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_TRGO) || \ + ((REGTRIG) == ADC_EXTERNALTRIGCONV_Ext_IT11)|| \ + ((REGTRIG) == ADC_SOFTWARE_START)) +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DATAALIGN_RIGHT) || \ + ((ALIGN) == ADC_DATAALIGN_LEFT)) +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SAMPLETIME_3CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_15CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_28CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_56CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_84CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_112CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_144CYCLES) || \ + ((TIME) == ADC_SAMPLETIME_480CYCLES)) +#define IS_ADC_EOCSelection(EOCSelection) (((EOCSelection) == ADC_EOC_SINGLE_CONV) || \ + ((EOCSelection) == ADC_EOC_SEQ_CONV) || \ + ((EOCSelection) == ADC_EOC_SINGLE_SEQ_CONV)) +#define IS_ADC_EVENT_TYPE(EVENT) (((EVENT) == ADC_AWD_EVENT) || \ + ((EVENT) == ADC_OVR_EVENT)) +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REG) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_INJEC) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REGINJEC) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REG) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_INJEC) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REGINJEC) || \ + ((WATCHDOG) == ADC_ANALOGWATCHDOG_NONE)) +#define IS_ADC_CHANNELS_TYPE(CHANNEL_TYPE) (((CHANNEL_TYPE) == ADC_ALL_CHANNELS) || \ + ((CHANNEL_TYPE) == ADC_REGULAR_CHANNELS) || \ + ((CHANNEL_TYPE) == ADC_INJECTED_CHANNELS)) +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFFU) + +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 16U)) +#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= (16U))) +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 1U) && ((NUMBER) <= 8U)) +#define IS_ADC_RANGE(RESOLUTION, ADC_VALUE) \ + ((((RESOLUTION) == ADC_RESOLUTION_12B) && ((ADC_VALUE) <= 0x0FFFU)) || \ + (((RESOLUTION) == ADC_RESOLUTION_10B) && ((ADC_VALUE) <= 0x03FFU)) || \ + (((RESOLUTION) == ADC_RESOLUTION_8B) && ((ADC_VALUE) <= 0x00FFU)) || \ + (((RESOLUTION) == ADC_RESOLUTION_6B) && ((ADC_VALUE) <= 0x003FU))) + +/** + * @brief Set ADC Regular channel sequence length. + * @param _NbrOfConversion_ Regular channel sequence length. + * @retval None + */ +#define ADC_SQR1(_NbrOfConversion_) (((_NbrOfConversion_) - (uint8_t)1U) << 20U) + +/** + * @brief Set the ADC's sample time for channel numbers between 10 and 18. + * @param _SAMPLETIME_ Sample time parameter. + * @param _CHANNELNB_ Channel number. + * @retval None + */ +#define ADC_SMPR1(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * (((uint32_t)((uint16_t)(_CHANNELNB_))) - 10U))) + +/** + * @brief Set the ADC's sample time for channel numbers between 0 and 9. + * @param _SAMPLETIME_ Sample time parameter. + * @param _CHANNELNB_ Channel number. + * @retval None + */ +#define ADC_SMPR2(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * ((uint32_t)((uint16_t)(_CHANNELNB_))))) + +/** + * @brief Set the selected regular channel rank for rank between 1 and 6. + * @param _CHANNELNB_ Channel number. + * @param _RANKNB_ Rank number. + * @retval None + */ +#define ADC_SQR3_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 1U))) + +/** + * @brief Set the selected regular channel rank for rank between 7 and 12. + * @param _CHANNELNB_ Channel number. + * @param _RANKNB_ Rank number. + * @retval None + */ +#define ADC_SQR2_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 7U))) + +/** + * @brief Set the selected regular channel rank for rank between 13 and 16. + * @param _CHANNELNB_ Channel number. + * @param _RANKNB_ Rank number. + * @retval None + */ +#define ADC_SQR1_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 13U))) + +/** + * @brief Enable ADC continuous conversion mode. + * @param _CONTINUOUS_MODE_ Continuous mode. + * @retval None + */ +#define ADC_CR2_CONTINUOUS(_CONTINUOUS_MODE_) ((_CONTINUOUS_MODE_) << 1U) + +/** + * @brief Configures the number of discontinuous conversions for the regular group channels. + * @param _NBR_DISCONTINUOUSCONV_ Number of discontinuous conversions. + * @retval None + */ +#define ADC_CR1_DISCONTINUOUS(_NBR_DISCONTINUOUSCONV_) (((_NBR_DISCONTINUOUSCONV_) - 1U) << ADC_CR1_DISCNUM_Pos) + +/** + * @brief Enable ADC scan mode. + * @param _SCANCONV_MODE_ Scan conversion mode. + * @retval None + */ +#define ADC_CR1_SCANCONV(_SCANCONV_MODE_) ((_SCANCONV_MODE_) << 8U) + +/** + * @brief Enable the ADC end of conversion selection. + * @param _EOCSelection_MODE_ End of conversion selection mode. + * @retval None + */ +#define ADC_CR2_EOCSelection(_EOCSelection_MODE_) ((_EOCSelection_MODE_) << 10U) + +/** + * @brief Enable the ADC DMA continuous request. + * @param _DMAContReq_MODE_ DMA continuous request mode. + * @retval None + */ +#define ADC_CR2_DMAContReq(_DMAContReq_MODE_) ((_DMAContReq_MODE_) << 9U) + +/** + * @brief Return resolution bits in CR1 register. + * @param __HANDLE__ ADC handle + * @retval None + */ +#define ADC_GET_RESOLUTION(__HANDLE__) (((__HANDLE__)->Instance->CR1) & ADC_CR1_RES) + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup ADC_Private_Functions ADC Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_ADC_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h new file mode 100644 index 0000000..f6e9ba0 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h @@ -0,0 +1,407 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc_ex.h + * @author MCD Application Team + * @brief Header file of ADC HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_ADC_EX_H +#define __STM32F4xx_ADC_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup ADCEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup ADCEx_Exported_Types ADC Exported Types + * @{ + */ + +/** + * @brief ADC Configuration injected Channel structure definition + * @note Parameters of this structure are shared within 2 scopes: + * - Scope channel: InjectedChannel, InjectedRank, InjectedSamplingTime, InjectedOffset + * - Scope injected group (affects all channels of injected group): InjectedNbrOfConversion, InjectedDiscontinuousConvMode, + * AutoInjectedConv, ExternalTrigInjecConvEdge, ExternalTrigInjecConv. + * @note The setting of these parameters with function HAL_ADCEx_InjectedConfigChannel() is conditioned to ADC state. + * ADC state can be either: + * - For all parameters: ADC disabled + * - For all except parameters 'InjectedDiscontinuousConvMode' and 'AutoInjectedConv': ADC enabled without conversion on going on injected group. + * - For parameters 'ExternalTrigInjecConv' and 'ExternalTrigInjecConvEdge': ADC enabled, even with conversion on going on injected group. + */ +typedef struct +{ + uint32_t InjectedChannel; /*!< Selection of ADC channel to configure + This parameter can be a value of @ref ADC_channels + Note: Depending on devices, some channels may not be available on package pins. Refer to device datasheet for channels availability. */ + uint32_t InjectedRank; /*!< Rank in the injected group sequencer + This parameter must be a value of @ref ADCEx_injected_rank + Note: In case of need to disable a channel or change order of conversion sequencer, rank containing a previous channel setting can be overwritten by the new channel setting (or parameter number of conversions can be adjusted) */ + uint32_t InjectedSamplingTime; /*!< Sampling time value to be set for the selected channel. + Unit: ADC clock cycles + Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). + This parameter can be a value of @ref ADC_sampling_times + Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. + If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. + Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), + sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) + Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ + uint32_t InjectedOffset; /*!< Defines the offset to be subtracted from the raw converted data (for channels set on injected group only). + Offset value must be a positive number. + Depending of ADC resolution selected (12, 10, 8 or 6 bits), + this parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF, 0x3FF, 0xFF or 0x3F respectively. */ + uint32_t InjectedNbrOfConversion; /*!< Specifies the number of ranks that will be converted within the injected group sequencer. + To use the injected group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. + This parameter must be a number between Min_Data = 1 and Max_Data = 4. + Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to + configure a channel on injected group can impact the configuration of other channels previously set. */ + FunctionalState InjectedDiscontinuousConvMode; /*!< Specifies whether the conversions sequence of injected group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). + Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. + Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. + This parameter can be set to ENABLE or DISABLE. + Note: For injected group, number of discontinuous ranks increment is fixed to one-by-one. + Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to + configure a channel on injected group can impact the configuration of other channels previously set. */ + FunctionalState AutoInjectedConv; /*!< Enables or disables the selected ADC automatic injected group conversion after regular one + This parameter can be set to ENABLE or DISABLE. + Note: To use Automatic injected conversion, discontinuous mode must be disabled ('DiscontinuousConvMode' and 'InjectedDiscontinuousConvMode' set to DISABLE) + Note: To use Automatic injected conversion, injected group external triggers must be disabled ('ExternalTrigInjecConv' set to ADC_SOFTWARE_START) + Note: In case of DMA used with regular group: if DMA configured in normal mode (single shot) JAUTO will be stopped upon DMA transfer complete. + To maintain JAUTO always enabled, DMA must be configured in circular mode. + Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to + configure a channel on injected group can impact the configuration of other channels previously set. */ + uint32_t ExternalTrigInjecConv; /*!< Selects the external event used to trigger the conversion start of injected group. + If set to ADC_INJECTED_SOFTWARE_START, external triggers are disabled. + If set to external trigger source, triggering is on event rising edge. + This parameter can be a value of @ref ADCEx_External_trigger_Source_Injected + Note: This parameter must be modified when ADC is disabled (before ADC start conversion or after ADC stop conversion). + If ADC is enabled, this parameter setting is bypassed without error reporting (as it can be the expected behaviour in case of another parameter update on the fly) + Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to + configure a channel on injected group can impact the configuration of other channels previously set. */ + uint32_t ExternalTrigInjecConvEdge; /*!< Selects the external trigger edge of injected group. + This parameter can be a value of @ref ADCEx_External_trigger_edge_Injected. + If trigger is set to ADC_INJECTED_SOFTWARE_START, this parameter is discarded. + Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to + configure a channel on injected group can impact the configuration of other channels previously set. */ +}ADC_InjectionConfTypeDef; + +/** + * @brief ADC Configuration multi-mode structure definition + */ +typedef struct +{ + uint32_t Mode; /*!< Configures the ADC to operate in independent or multi mode. + This parameter can be a value of @ref ADCEx_Common_mode */ + uint32_t DMAAccessMode; /*!< Configures the Direct memory access mode for multi ADC mode. + This parameter can be a value of @ref ADCEx_Direct_memory_access_mode_for_multi_mode */ + uint32_t TwoSamplingDelay; /*!< Configures the Delay between 2 sampling phases. + This parameter can be a value of @ref ADC_delay_between_2_sampling_phases */ +}ADC_MultiModeTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup ADCEx_Exported_Constants ADC Exported Constants + * @{ + */ + +/** @defgroup ADCEx_Common_mode ADC Common Mode + * @{ + */ +#define ADC_MODE_INDEPENDENT 0x00000000U +#define ADC_DUALMODE_REGSIMULT_INJECSIMULT ((uint32_t)ADC_CCR_MULTI_0) +#define ADC_DUALMODE_REGSIMULT_ALTERTRIG ((uint32_t)ADC_CCR_MULTI_1) +#define ADC_DUALMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) +#define ADC_DUALMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) +#define ADC_DUALMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) +#define ADC_DUALMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) +#define ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0)) +#define ADC_TRIPLEMODE_REGSIMULT_AlterTrig ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1)) +#define ADC_TRIPLEMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) +#define ADC_TRIPLEMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) +#define ADC_TRIPLEMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) +#define ADC_TRIPLEMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) +/** + * @} + */ + +/** @defgroup ADCEx_Direct_memory_access_mode_for_multi_mode ADC Direct Memory Access Mode For Multi Mode + * @{ + */ +#define ADC_DMAACCESSMODE_DISABLED 0x00000000U /*!< DMA mode disabled */ +#define ADC_DMAACCESSMODE_1 ((uint32_t)ADC_CCR_DMA_0) /*!< DMA mode 1 enabled (2 / 3 half-words one by one - 1 then 2 then 3)*/ +#define ADC_DMAACCESSMODE_2 ((uint32_t)ADC_CCR_DMA_1) /*!< DMA mode 2 enabled (2 / 3 half-words by pairs - 2&1 then 1&3 then 3&2)*/ +#define ADC_DMAACCESSMODE_3 ((uint32_t)ADC_CCR_DMA) /*!< DMA mode 3 enabled (2 / 3 bytes by pairs - 2&1 then 1&3 then 3&2) */ +/** + * @} + */ + +/** @defgroup ADCEx_External_trigger_edge_Injected ADC External Trigger Edge Injected + * @{ + */ +#define ADC_EXTERNALTRIGINJECCONVEDGE_NONE 0x00000000U +#define ADC_EXTERNALTRIGINJECCONVEDGE_RISING ((uint32_t)ADC_CR2_JEXTEN_0) +#define ADC_EXTERNALTRIGINJECCONVEDGE_FALLING ((uint32_t)ADC_CR2_JEXTEN_1) +#define ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_JEXTEN) +/** + * @} + */ + +/** @defgroup ADCEx_External_trigger_Source_Injected ADC External Trigger Source Injected + * @{ + */ +#define ADC_EXTERNALTRIGINJECCONV_T1_CC4 0x00000000U +#define ADC_EXTERNALTRIGINJECCONV_T1_TRGO ((uint32_t)ADC_CR2_JEXTSEL_0) +#define ADC_EXTERNALTRIGINJECCONV_T2_CC1 ((uint32_t)ADC_CR2_JEXTSEL_1) +#define ADC_EXTERNALTRIGINJECCONV_T2_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T3_CC2 ((uint32_t)ADC_CR2_JEXTSEL_2) +#define ADC_EXTERNALTRIGINJECCONV_T3_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T4_CC1 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) +#define ADC_EXTERNALTRIGINJECCONV_T4_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T4_CC3 ((uint32_t)ADC_CR2_JEXTSEL_3) +#define ADC_EXTERNALTRIGINJECCONV_T4_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T5_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1)) +#define ADC_EXTERNALTRIGINJECCONV_T5_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T8_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2)) +#define ADC_EXTERNALTRIGINJECCONV_T8_CC3 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) +#define ADC_EXTERNALTRIGINJECCONV_T8_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) +#define ADC_EXTERNALTRIGINJECCONV_EXT_IT15 ((uint32_t)ADC_CR2_JEXTSEL) +#define ADC_INJECTED_SOFTWARE_START ((uint32_t)ADC_CR2_JEXTSEL + 1U) +/** + * @} + */ + +/** @defgroup ADCEx_injected_rank ADC Injected Rank + * @{ + */ +#define ADC_INJECTED_RANK_1 0x00000001U +#define ADC_INJECTED_RANK_2 0x00000002U +#define ADC_INJECTED_RANK_3 0x00000003U +#define ADC_INJECTED_RANK_4 0x00000004U +/** + * @} + */ + +/** @defgroup ADCEx_channels ADC Specific Channels + * @{ + */ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ + defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ + defined(STM32F412Cx) +#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_16) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F412Zx || + STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ + defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ +#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_18 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) +#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup ADC_Exported_Macros ADC Exported Macros + * @{ + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) +/** + * @brief Disable internal path of ADC channel Vbat + * @note Use case of this macro: + * On devices STM32F42x and STM32F43x, ADC internal channels + * Vbat and VrefInt share the same internal path, only + * one of them can be enabled.This macro is to be used when ADC + * channels Vbat and VrefInt are selected, and must be called + * before starting conversion of ADC channel VrefInt in order + * to disable ADC channel Vbat. + * @retval None + */ +#define __HAL_ADC_PATH_INTERNAL_VBAT_DISABLE() (ADC->CCR &= ~(ADC_CCR_VBATE)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup ADCEx_Exported_Functions + * @{ + */ + +/** @addtogroup ADCEx_Exported_Functions_Group1 + * @{ + */ + +/* I/O operation functions ******************************************************/ +HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); +HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc); +HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc); +uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank); +HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); +HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc); +uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc); +void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc); + +/* Peripheral Control functions *************************************************/ +HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc,ADC_InjectionConfTypeDef* sConfigInjected); +HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode); + +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup ADCEx_Private_Constants ADC Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup ADCEx_Private_Macros ADC Private Macros + * @{ + */ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ + defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ + defined(STM32F412Cx) +#define IS_ADC_CHANNEL(CHANNEL) ((CHANNEL) <= ADC_CHANNEL_18) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || + STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || \ + defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) <= ADC_CHANNEL_18) || \ + ((CHANNEL) == ADC_CHANNEL_TEMPSENSOR)) +#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#define IS_ADC_MODE(MODE) (((MODE) == ADC_MODE_INDEPENDENT) || \ + ((MODE) == ADC_DUALMODE_REGSIMULT_INJECSIMULT) || \ + ((MODE) == ADC_DUALMODE_REGSIMULT_ALTERTRIG) || \ + ((MODE) == ADC_DUALMODE_INJECSIMULT) || \ + ((MODE) == ADC_DUALMODE_REGSIMULT) || \ + ((MODE) == ADC_DUALMODE_INTERL) || \ + ((MODE) == ADC_DUALMODE_ALTERTRIG) || \ + ((MODE) == ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT) || \ + ((MODE) == ADC_TRIPLEMODE_REGSIMULT_AlterTrig) || \ + ((MODE) == ADC_TRIPLEMODE_INJECSIMULT) || \ + ((MODE) == ADC_TRIPLEMODE_REGSIMULT) || \ + ((MODE) == ADC_TRIPLEMODE_INTERL) || \ + ((MODE) == ADC_TRIPLEMODE_ALTERTRIG)) +#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAACCESSMODE_DISABLED) || \ + ((MODE) == ADC_DMAACCESSMODE_1) || \ + ((MODE) == ADC_DMAACCESSMODE_2) || \ + ((MODE) == ADC_DMAACCESSMODE_3)) +#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_NONE) || \ + ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISING) || \ + ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_FALLING) || \ + ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING)) +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_CC4) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_TRGO) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_CC1) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_TRGO) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC2) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC4) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC1) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC2) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC3) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_TRGO) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_CC4) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_TRGO) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC2) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC3) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC4) || \ + ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_EXT_IT15)|| \ + ((INJTRIG) == ADC_INJECTED_SOFTWARE_START)) +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 4U)) +#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= 4U)) + +/** + * @brief Set the selected injected Channel rank. + * @param _CHANNELNB_ Channel number. + * @param _RANKNB_ Rank number. + * @param _JSQR_JL_ Sequence length. + * @retval None + */ +#define ADC_JSQR(_CHANNELNB_, _RANKNB_, _JSQR_JL_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * (uint8_t)(((_RANKNB_) + 3U) - (_JSQR_JL_)))) + +/** + * @brief Defines if the selected ADC is within ADC common register ADC123 or ADC1 + * if available (ADC2, ADC3 availability depends on STM32 product) + * @param __HANDLE__ ADC handle + * @retval Common control register ADC123 or ADC1 + */ +#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define ADC_COMMON_REGISTER(__HANDLE__) ADC123_COMMON +#else +#define ADC_COMMON_REGISTER(__HANDLE__) ADC1_COMMON +#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx || STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup ADCEx_Private_Functions ADC Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_ADC_EX_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h index aa4a40d..728b61c 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h @@ -1,844 +1,844 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.h - * @author MCD Application Team - * @brief Header file of CAN HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CAN_H -#define STM32F4xx_HAL_CAN_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (CAN1) -/** @addtogroup CAN - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Types CAN Exported Types - * @{ - */ -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ - HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ - HAL_CAN_STATE_LISTENING = 0x02U, /*!< CAN receive process is ongoing */ - HAL_CAN_STATE_SLEEP_PENDING = 0x03U, /*!< CAN sleep request is pending */ - HAL_CAN_STATE_SLEEP_ACTIVE = 0x04U, /*!< CAN sleep mode is active */ - HAL_CAN_STATE_ERROR = 0x05U /*!< CAN error state */ - -} HAL_CAN_StateTypeDef; - -/** - * @brief CAN init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the length of a time quantum. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024. */ - - uint32_t Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint32_t SyncJumpWidth; /*!< Specifies the maximum number of time quanta the CAN hardware - is allowed to lengthen or shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint32_t TimeSeg1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint32_t TimeSeg2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - FunctionalState TimeTriggeredMode; /*!< Enable or disable the time triggered communication mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoBusOff; /*!< Enable or disable the automatic bus-off management. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoWakeUp; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoRetransmission; /*!< Enable or disable the non-automatic retransmission mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState ReceiveFifoLocked; /*!< Enable or disable the Receive FIFO Locked mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState TransmitFifoPriority;/*!< Enable or disable the transmit FIFO priority. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_InitTypeDef; - -/** - * @brief CAN filter configuration structure definition - */ -typedef struct -{ - uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1U) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint32_t FilterBank; /*!< Specifies the filter bank which will be initialized. - For single CAN instance(14 dedicated filter banks), - this parameter must be a number between Min_Data = 0 and Max_Data = 13. - For dual CAN instances(28 filter banks shared), - this parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - - uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint32_t FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - uint32_t FilterActivation; /*!< Enable or disable the filter. - This parameter can be a value of @ref CAN_filter_activation */ - - uint32_t SlaveStartFilterBank; /*!< Select the start filter bank for the slave CAN instance. - For single CAN instances, this parameter is meaningless. - For dual CAN instances, all filter banks with lower index are assigned to master - CAN instance, whereas all filter banks with greater index are assigned to slave - CAN instance. - This parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - -} CAN_FilterTypeDef; - -/** - * @brief CAN Tx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - FunctionalState TransmitGlobalTime; /*!< Specifies whether the timestamp counter value captured on start - of frame transmission, is sent in DATA6 and DATA7 replacing pData[6] and pData[7]. - @note: Time Triggered Communication Mode must be enabled. - @note: DLC must be programmed as 8 bytes, in order these 2 bytes are sent. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_TxHeaderTypeDef; - -/** - * @brief CAN Rx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - uint32_t Timestamp; /*!< Specifies the timestamp counter value captured on start of frame reception. - @note: Time Triggered Communication Mode must be enabled. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFFFF. */ - - uint32_t FilterMatchIndex; /*!< Specifies the index of matching acceptance filter element. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF. */ - -} CAN_RxHeaderTypeDef; - -/** - * @brief CAN handle Structure definition - */ -typedef struct __CAN_HandleTypeDef -{ - CAN_TypeDef *Instance; /*!< Register base address */ - - CAN_InitTypeDef Init; /*!< CAN required parameters */ - - __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ - - __IO uint32_t ErrorCode; /*!< CAN Error code. - This parameter can be a value of @ref CAN_Error_Code */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - void (* TxMailbox0CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 0 complete callback */ - void (* TxMailbox1CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 1 complete callback */ - void (* TxMailbox2CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 2 complete callback */ - void (* TxMailbox0AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 0 abort callback */ - void (* TxMailbox1AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 1 abort callback */ - void (* TxMailbox2AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 2 abort callback */ - void (* RxFifo0MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 msg pending callback */ - void (* RxFifo0FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 full callback */ - void (* RxFifo1MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 msg pending callback */ - void (* RxFifo1FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 full callback */ - void (* SleepCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Sleep callback */ - void (* WakeUpFromRxMsgCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Wake Up from Rx msg callback */ - void (* ErrorCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Error callback */ - - void (* MspInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp Init callback */ - void (* MspDeInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp DeInit callback */ - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -} CAN_HandleTypeDef; - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/** - * @brief HAL CAN common Callback ID enumeration definition - */ -typedef enum -{ - HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID = 0x00U, /*!< CAN Tx Mailbox 0 complete callback ID */ - HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID = 0x01U, /*!< CAN Tx Mailbox 1 complete callback ID */ - HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID = 0x02U, /*!< CAN Tx Mailbox 2 complete callback ID */ - HAL_CAN_TX_MAILBOX0_ABORT_CB_ID = 0x03U, /*!< CAN Tx Mailbox 0 abort callback ID */ - HAL_CAN_TX_MAILBOX1_ABORT_CB_ID = 0x04U, /*!< CAN Tx Mailbox 1 abort callback ID */ - HAL_CAN_TX_MAILBOX2_ABORT_CB_ID = 0x05U, /*!< CAN Tx Mailbox 2 abort callback ID */ - HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID = 0x06U, /*!< CAN Rx FIFO 0 message pending callback ID */ - HAL_CAN_RX_FIFO0_FULL_CB_ID = 0x07U, /*!< CAN Rx FIFO 0 full callback ID */ - HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID = 0x08U, /*!< CAN Rx FIFO 1 message pending callback ID */ - HAL_CAN_RX_FIFO1_FULL_CB_ID = 0x09U, /*!< CAN Rx FIFO 1 full callback ID */ - HAL_CAN_SLEEP_CB_ID = 0x0AU, /*!< CAN Sleep callback ID */ - HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID = 0x0BU, /*!< CAN Wake Up from Rx msg callback ID */ - HAL_CAN_ERROR_CB_ID = 0x0CU, /*!< CAN Error callback ID */ - - HAL_CAN_MSPINIT_CB_ID = 0x0DU, /*!< CAN MspInit callback ID */ - HAL_CAN_MSPDEINIT_CB_ID = 0x0EU, /*!< CAN MspDeInit callback ID */ - -} HAL_CAN_CallbackIDTypeDef; - -/** - * @brief HAL CAN Callback pointer definition - */ -typedef void (*pCAN_CallbackTypeDef)(CAN_HandleTypeDef *hcan); /*!< pointer to a CAN callback function */ - -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CAN_Exported_Constants CAN Exported Constants - * @{ - */ - -/** @defgroup CAN_Error_Code CAN Error Code - * @{ - */ -#define HAL_CAN_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_CAN_ERROR_EWG (0x00000001U) /*!< Protocol Error Warning */ -#define HAL_CAN_ERROR_EPV (0x00000002U) /*!< Error Passive */ -#define HAL_CAN_ERROR_BOF (0x00000004U) /*!< Bus-off error */ -#define HAL_CAN_ERROR_STF (0x00000008U) /*!< Stuff error */ -#define HAL_CAN_ERROR_FOR (0x00000010U) /*!< Form error */ -#define HAL_CAN_ERROR_ACK (0x00000020U) /*!< Acknowledgment error */ -#define HAL_CAN_ERROR_BR (0x00000040U) /*!< Bit recessive error */ -#define HAL_CAN_ERROR_BD (0x00000080U) /*!< Bit dominant error */ -#define HAL_CAN_ERROR_CRC (0x00000100U) /*!< CRC error */ -#define HAL_CAN_ERROR_RX_FOV0 (0x00000200U) /*!< Rx FIFO0 overrun error */ -#define HAL_CAN_ERROR_RX_FOV1 (0x00000400U) /*!< Rx FIFO1 overrun error */ -#define HAL_CAN_ERROR_TX_ALST0 (0x00000800U) /*!< TxMailbox 0 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR0 (0x00001000U) /*!< TxMailbox 0 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST1 (0x00002000U) /*!< TxMailbox 1 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR1 (0x00004000U) /*!< TxMailbox 1 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST2 (0x00008000U) /*!< TxMailbox 2 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR2 (0x00010000U) /*!< TxMailbox 2 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TIMEOUT (0x00020000U) /*!< Timeout error */ -#define HAL_CAN_ERROR_NOT_INITIALIZED (0x00040000U) /*!< Peripheral not initialized */ -#define HAL_CAN_ERROR_NOT_READY (0x00080000U) /*!< Peripheral not ready */ -#define HAL_CAN_ERROR_NOT_STARTED (0x00100000U) /*!< Peripheral not started */ -#define HAL_CAN_ERROR_PARAM (0x00200000U) /*!< Parameter error */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define HAL_CAN_ERROR_INVALID_CALLBACK (0x00400000U) /*!< Invalid Callback error */ -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -#define HAL_CAN_ERROR_INTERNAL (0x00800000U) /*!< Internal error */ - -/** - * @} - */ - -/** @defgroup CAN_InitStatus CAN InitStatus - * @{ - */ -#define CAN_INITSTATUS_FAILED (0x00000000U) /*!< CAN initialization failed */ -#define CAN_INITSTATUS_SUCCESS (0x00000001U) /*!< CAN initialization OK */ -/** - * @} - */ - -/** @defgroup CAN_operating_mode CAN Operating Mode - * @{ - */ -#define CAN_MODE_NORMAL (0x00000000U) /*!< Normal mode */ -#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ -#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ -#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ -/** - * @} - */ - - -/** @defgroup CAN_synchronisation_jump_width CAN Synchronization Jump Width - * @{ - */ -#define CAN_SJW_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ -#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ -#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in Bit Segment 1 - * @{ - */ -#define CAN_BS1_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ -#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ -#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ -#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ -#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ -#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ -#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ -#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ -#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ -#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ -#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ -#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ -#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ -#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ -#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in Bit Segment 2 - * @{ - */ -#define CAN_BS2_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ -#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ -#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ -#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ -#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ -#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ -#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode CAN Filter Mode - * @{ - */ -#define CAN_FILTERMODE_IDMASK (0x00000000U) /*!< Identifier mask mode */ -#define CAN_FILTERMODE_IDLIST (0x00000001U) /*!< Identifier list mode */ -/** - * @} - */ - -/** @defgroup CAN_filter_scale CAN Filter Scale - * @{ - */ -#define CAN_FILTERSCALE_16BIT (0x00000000U) /*!< Two 16-bit filters */ -#define CAN_FILTERSCALE_32BIT (0x00000001U) /*!< One 32-bit filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_activation CAN Filter Activation - * @{ - */ -#define CAN_FILTER_DISABLE (0x00000000U) /*!< Disable filter */ -#define CAN_FILTER_ENABLE (0x00000001U) /*!< Enable filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO CAN Filter FIFO - * @{ - */ -#define CAN_FILTER_FIFO0 (0x00000000U) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FILTER_FIFO1 (0x00000001U) /*!< Filter FIFO 1 assignment for filter x */ -/** - * @} - */ - -/** @defgroup CAN_identifier_type CAN Identifier Type - * @{ - */ -#define CAN_ID_STD (0x00000000U) /*!< Standard Id */ -#define CAN_ID_EXT (0x00000004U) /*!< Extended Id */ -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request - * @{ - */ -#define CAN_RTR_DATA (0x00000000U) /*!< Data frame */ -#define CAN_RTR_REMOTE (0x00000002U) /*!< Remote frame */ -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number CAN Receive FIFO Number - * @{ - */ -#define CAN_RX_FIFO0 (0x00000000U) /*!< CAN receive FIFO 0 */ -#define CAN_RX_FIFO1 (0x00000001U) /*!< CAN receive FIFO 1 */ -/** - * @} - */ - -/** @defgroup CAN_Tx_Mailboxes CAN Tx Mailboxes - * @{ - */ -#define CAN_TX_MAILBOX0 (0x00000001U) /*!< Tx Mailbox 0 */ -#define CAN_TX_MAILBOX1 (0x00000002U) /*!< Tx Mailbox 1 */ -#define CAN_TX_MAILBOX2 (0x00000004U) /*!< Tx Mailbox 2 */ -/** - * @} - */ - -/** @defgroup CAN_flags CAN Flags - * @{ - */ -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 (0x00000500U) /*!< Request complete MailBox 0 flag */ -#define CAN_FLAG_TXOK0 (0x00000501U) /*!< Transmission OK MailBox 0 flag */ -#define CAN_FLAG_ALST0 (0x00000502U) /*!< Arbitration Lost MailBox 0 flag */ -#define CAN_FLAG_TERR0 (0x00000503U) /*!< Transmission error MailBox 0 flag */ -#define CAN_FLAG_RQCP1 (0x00000508U) /*!< Request complete MailBox1 flag */ -#define CAN_FLAG_TXOK1 (0x00000509U) /*!< Transmission OK MailBox 1 flag */ -#define CAN_FLAG_ALST1 (0x0000050AU) /*!< Arbitration Lost MailBox 1 flag */ -#define CAN_FLAG_TERR1 (0x0000050BU) /*!< Transmission error MailBox 1 flag */ -#define CAN_FLAG_RQCP2 (0x00000510U) /*!< Request complete MailBox2 flag */ -#define CAN_FLAG_TXOK2 (0x00000511U) /*!< Transmission OK MailBox 2 flag */ -#define CAN_FLAG_ALST2 (0x00000512U) /*!< Arbitration Lost MailBox 2 flag */ -#define CAN_FLAG_TERR2 (0x00000513U) /*!< Transmission error MailBox 2 flag */ -#define CAN_FLAG_TME0 (0x0000051AU) /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME1 (0x0000051BU) /*!< Transmit mailbox 1 empty flag */ -#define CAN_FLAG_TME2 (0x0000051CU) /*!< Transmit mailbox 2 empty flag */ -#define CAN_FLAG_LOW0 (0x0000051DU) /*!< Lowest priority mailbox 0 flag */ -#define CAN_FLAG_LOW1 (0x0000051EU) /*!< Lowest priority mailbox 1 flag */ -#define CAN_FLAG_LOW2 (0x0000051FU) /*!< Lowest priority mailbox 2 flag */ - -/* Receive Flags */ -#define CAN_FLAG_FF0 (0x00000203U) /*!< RX FIFO 0 Full flag */ -#define CAN_FLAG_FOV0 (0x00000204U) /*!< RX FIFO 0 Overrun flag */ -#define CAN_FLAG_FF1 (0x00000403U) /*!< RX FIFO 1 Full flag */ -#define CAN_FLAG_FOV1 (0x00000404U) /*!< RX FIFO 1 Overrun flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_INAK (0x00000100U) /*!< Initialization acknowledge flag */ -#define CAN_FLAG_SLAK (0x00000101U) /*!< Sleep acknowledge flag */ -#define CAN_FLAG_ERRI (0x00000102U) /*!< Error flag */ -#define CAN_FLAG_WKU (0x00000103U) /*!< Wake up interrupt flag */ -#define CAN_FLAG_SLAKI (0x00000104U) /*!< Sleep acknowledge interrupt flag */ - -/* Error Flags */ -#define CAN_FLAG_EWG (0x00000300U) /*!< Error warning flag */ -#define CAN_FLAG_EPV (0x00000301U) /*!< Error passive flag */ -#define CAN_FLAG_BOF (0x00000302U) /*!< Bus-Off flag */ -/** - * @} - */ - - -/** @defgroup CAN_Interrupts CAN Interrupts - * @{ - */ -/* Transmit Interrupt */ -#define CAN_IT_TX_MAILBOX_EMPTY ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ - -/* Receive Interrupts */ -#define CAN_IT_RX_FIFO0_MSG_PENDING ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ -#define CAN_IT_RX_FIFO0_FULL ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ -#define CAN_IT_RX_FIFO0_OVERRUN ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ -#define CAN_IT_RX_FIFO1_MSG_PENDING ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ -#define CAN_IT_RX_FIFO1_FULL ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ -#define CAN_IT_RX_FIFO1_OVERRUN ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ - -/* Operating Mode Interrupts */ -#define CAN_IT_WAKEUP ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ -#define CAN_IT_SLEEP_ACK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ - -/* Error Interrupts */ -#define CAN_IT_ERROR_WARNING ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ -#define CAN_IT_ERROR_PASSIVE ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ -#define CAN_IT_BUSOFF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ -#define CAN_IT_LAST_ERROR_CODE ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ -#define CAN_IT_ERROR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CAN_Exported_Macros CAN Exported Macros - * @{ - */ - -/** @brief Reset CAN handle state - * @param __HANDLE__ CAN handle. - * @retval None - */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_CAN_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) -#endif /*USE_HAL_CAN_REGISTER_CALLBACKS */ - -/** - * @brief Enable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to enable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) - -/** - * @brief Disable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to disable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) - -/** @brief Check if the specified CAN interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the CAN Handle. - * @param __INTERRUPT__ specifies the CAN interrupt source to check. - * This parameter can be a value of @arg CAN_Interrupts - * @retval The state of __IT__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) & (__INTERRUPT__)) - -/** @brief Check whether the specified CAN flag is set or not. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of @arg CAN_flags - * @retval The state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 3U)? ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** @brief Clear the specified CAN pending flag. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_FLAG_RQCP0: Request complete MailBox 0 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox 0 Flag - * @arg CAN_FLAG_ALST0: Arbitration Lost MailBox 0 Flag - * @arg CAN_FLAG_TERR0: Transmission error MailBox 0 Flag - * @arg CAN_FLAG_RQCP1: Request complete MailBox 1 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox 1 Flag - * @arg CAN_FLAG_ALST1: Arbitration Lost MailBox 1 Flag - * @arg CAN_FLAG_TERR1: Transmission error MailBox 1 Flag - * @arg CAN_FLAG_RQCP2: Request complete MailBox 2 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox 2 Flag - * @arg CAN_FLAG_ALST2: Arbitration Lost MailBox 2 Flag - * @arg CAN_FLAG_TERR2: Transmission error MailBox 2 Flag - * @arg CAN_FLAG_FF0: RX FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: RX FIFO 0 Overrun Flag - * @arg CAN_FLAG_FF1: RX FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: RX FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKUI: Wake up Interrupt Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Interrupt Flag - * @retval None - */ -#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? (((__HANDLE__)->Instance->MSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @addtogroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * @{ - */ - -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)); -HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID); - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group2 Configuration functions - * @brief Configuration functions - * @{ - */ - -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group3 Control functions - * @brief Control functions - * @{ - */ - -/* Control functions **********************************************************/ -HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox); -HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox); -HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]); -uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group4 Interrupts management - * @brief Interrupts management - * @{ - */ -/* Interrupts management ******************************************************/ -HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs); -HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs); -void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group5 Callback functions - * @brief Callback functions - * @{ - */ -/* Callbacks functions ********************************************************/ - -void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group6 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CAN_Private_Types CAN Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Variables CAN Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_FLAG_MASK (0x000000FFU) -/** - * @} - */ - -/* Private Macros -----------------------------------------------------------*/ -/** @defgroup CAN_Private_Macros CAN Private Macros - * @{ - */ - -#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ - ((MODE) == CAN_MODE_LOOPBACK)|| \ - ((MODE) == CAN_MODE_SILENT) || \ - ((MODE) == CAN_MODE_SILENT_LOOPBACK)) -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ) || \ - ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) -#define IS_CAN_BS1(BS1) (((BS1) == CAN_BS1_1TQ) || ((BS1) == CAN_BS1_2TQ) || \ - ((BS1) == CAN_BS1_3TQ) || ((BS1) == CAN_BS1_4TQ) || \ - ((BS1) == CAN_BS1_5TQ) || ((BS1) == CAN_BS1_6TQ) || \ - ((BS1) == CAN_BS1_7TQ) || ((BS1) == CAN_BS1_8TQ) || \ - ((BS1) == CAN_BS1_9TQ) || ((BS1) == CAN_BS1_10TQ)|| \ - ((BS1) == CAN_BS1_11TQ)|| ((BS1) == CAN_BS1_12TQ)|| \ - ((BS1) == CAN_BS1_13TQ)|| ((BS1) == CAN_BS1_14TQ)|| \ - ((BS1) == CAN_BS1_15TQ)|| ((BS1) == CAN_BS1_16TQ)) -#define IS_CAN_BS2(BS2) (((BS2) == CAN_BS2_1TQ) || ((BS2) == CAN_BS2_2TQ) || \ - ((BS2) == CAN_BS2_3TQ) || ((BS2) == CAN_BS2_4TQ) || \ - ((BS2) == CAN_BS2_5TQ) || ((BS2) == CAN_BS2_6TQ) || \ - ((BS2) == CAN_BS2_7TQ) || ((BS2) == CAN_BS2_8TQ)) -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) -#define IS_CAN_FILTER_ID_HALFWORD(HALFWORD) ((HALFWORD) <= 0xFFFFU) -#define IS_CAN_FILTER_BANK_DUAL(BANK) ((BANK) <= 27U) -#define IS_CAN_FILTER_BANK_SINGLE(BANK) ((BANK) <= 13U) -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ - ((MODE) == CAN_FILTERMODE_IDLIST)) -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ - ((SCALE) == CAN_FILTERSCALE_32BIT)) -#define IS_CAN_FILTER_ACTIVATION(ACTIVATION) (((ACTIVATION) == CAN_FILTER_DISABLE) || \ - ((ACTIVATION) == CAN_FILTER_ENABLE)) -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ - ((FIFO) == CAN_FILTER_FIFO1)) -#define IS_CAN_TX_MAILBOX(TRANSMITMAILBOX) (((TRANSMITMAILBOX) == CAN_TX_MAILBOX0 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX1 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX2 )) -#define IS_CAN_TX_MAILBOX_LIST(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= (CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2)) -#define IS_CAN_STDID(STDID) ((STDID) <= 0x7FFU) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) -#define IS_CAN_DLC(DLC) ((DLC) <= 8U) -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ - ((IDTYPE) == CAN_ID_EXT)) -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) -#define IS_CAN_RX_FIFO(FIFO) (((FIFO) == CAN_RX_FIFO0) || ((FIFO) == CAN_RX_FIFO1)) -#define IS_CAN_IT(IT) ((IT) <= (CAN_IT_TX_MAILBOX_EMPTY | CAN_IT_RX_FIFO0_MSG_PENDING | \ - CAN_IT_RX_FIFO0_FULL | CAN_IT_RX_FIFO0_OVERRUN | \ - CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_RX_FIFO1_FULL | \ - CAN_IT_RX_FIFO1_OVERRUN | CAN_IT_WAKEUP | \ - CAN_IT_SLEEP_ACK | CAN_IT_ERROR_WARNING | \ - CAN_IT_ERROR_PASSIVE | CAN_IT_BUSOFF | \ - CAN_IT_LAST_ERROR_CODE | CAN_IT_ERROR)) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - - -#endif /* CAN1 */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_CAN_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_can.h + * @author MCD Application Team + * @brief Header file of CAN HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_CAN_H +#define STM32F4xx_HAL_CAN_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined (CAN1) +/** @addtogroup CAN + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup CAN_Exported_Types CAN Exported Types + * @{ + */ +/** + * @brief HAL State structures definition + */ +typedef enum +{ + HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ + HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ + HAL_CAN_STATE_LISTENING = 0x02U, /*!< CAN receive process is ongoing */ + HAL_CAN_STATE_SLEEP_PENDING = 0x03U, /*!< CAN sleep request is pending */ + HAL_CAN_STATE_SLEEP_ACTIVE = 0x04U, /*!< CAN sleep mode is active */ + HAL_CAN_STATE_ERROR = 0x05U /*!< CAN error state */ + +} HAL_CAN_StateTypeDef; + +/** + * @brief CAN init structure definition + */ +typedef struct +{ + uint32_t Prescaler; /*!< Specifies the length of a time quantum. + This parameter must be a number between Min_Data = 1 and Max_Data = 1024. */ + + uint32_t Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of @ref CAN_operating_mode */ + + uint32_t SyncJumpWidth; /*!< Specifies the maximum number of time quanta the CAN hardware + is allowed to lengthen or shorten a bit to perform resynchronization. + This parameter can be a value of @ref CAN_synchronisation_jump_width */ + + uint32_t TimeSeg1; /*!< Specifies the number of time quanta in Bit Segment 1. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ + + uint32_t TimeSeg2; /*!< Specifies the number of time quanta in Bit Segment 2. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState TimeTriggeredMode; /*!< Enable or disable the time triggered communication mode. + This parameter can be set to ENABLE or DISABLE. */ + + FunctionalState AutoBusOff; /*!< Enable or disable the automatic bus-off management. + This parameter can be set to ENABLE or DISABLE. */ + + FunctionalState AutoWakeUp; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set to ENABLE or DISABLE. */ + + FunctionalState AutoRetransmission; /*!< Enable or disable the non-automatic retransmission mode. + This parameter can be set to ENABLE or DISABLE. */ + + FunctionalState ReceiveFifoLocked; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set to ENABLE or DISABLE. */ + + FunctionalState TransmitFifoPriority;/*!< Enable or disable the transmit FIFO priority. + This parameter can be set to ENABLE or DISABLE. */ + +} CAN_InitTypeDef; + +/** + * @brief CAN filter configuration structure definition + */ +typedef struct +{ + uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ + + uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ + + uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ + + uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ + + uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1U) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint32_t FilterBank; /*!< Specifies the filter bank which will be initialized. + For single CAN instance(14 dedicated filter banks), + this parameter must be a number between Min_Data = 0 and Max_Data = 13. + For dual CAN instances(28 filter banks shared), + this parameter must be a number between Min_Data = 0 and Max_Data = 27. */ + + uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint32_t FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + uint32_t FilterActivation; /*!< Enable or disable the filter. + This parameter can be a value of @ref CAN_filter_activation */ + + uint32_t SlaveStartFilterBank; /*!< Select the start filter bank for the slave CAN instance. + For single CAN instances, this parameter is meaningless. + For dual CAN instances, all filter banks with lower index are assigned to master + CAN instance, whereas all filter banks with greater index are assigned to slave + CAN instance. + This parameter must be a number between Min_Data = 0 and Max_Data = 27. */ + +} CAN_FilterTypeDef; + +/** + * @brief CAN Tx message header structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ + + uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. + This parameter can be a value of @ref CAN_identifier_type */ + + uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. + This parameter can be a value of @ref CAN_remote_transmission_request */ + + uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. + This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ + + FunctionalState TransmitGlobalTime; /*!< Specifies whether the timestamp counter value captured on start + of frame transmission, is sent in DATA6 and DATA7 replacing pData[6] and pData[7]. + @note: Time Triggered Communication Mode must be enabled. + @note: DLC must be programmed as 8 bytes, in order these 2 bytes are sent. + This parameter can be set to ENABLE or DISABLE. */ + +} CAN_TxHeaderTypeDef; + +/** + * @brief CAN Rx message header structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ + + uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. + This parameter can be a value of @ref CAN_identifier_type */ + + uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. + This parameter can be a value of @ref CAN_remote_transmission_request */ + + uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. + This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ + + uint32_t Timestamp; /*!< Specifies the timestamp counter value captured on start of frame reception. + @note: Time Triggered Communication Mode must be enabled. + This parameter must be a number between Min_Data = 0 and Max_Data = 0xFFFF. */ + + uint32_t FilterMatchIndex; /*!< Specifies the index of matching acceptance filter element. + This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF. */ + +} CAN_RxHeaderTypeDef; + +/** + * @brief CAN handle Structure definition + */ +typedef struct __CAN_HandleTypeDef +{ + CAN_TypeDef *Instance; /*!< Register base address */ + + CAN_InitTypeDef Init; /*!< CAN required parameters */ + + __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ + + __IO uint32_t ErrorCode; /*!< CAN Error code. + This parameter can be a value of @ref CAN_Error_Code */ + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + void (* TxMailbox0CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 0 complete callback */ + void (* TxMailbox1CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 1 complete callback */ + void (* TxMailbox2CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 2 complete callback */ + void (* TxMailbox0AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 0 abort callback */ + void (* TxMailbox1AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 1 abort callback */ + void (* TxMailbox2AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 2 abort callback */ + void (* RxFifo0MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 msg pending callback */ + void (* RxFifo0FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 full callback */ + void (* RxFifo1MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 msg pending callback */ + void (* RxFifo1FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 full callback */ + void (* SleepCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Sleep callback */ + void (* WakeUpFromRxMsgCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Wake Up from Rx msg callback */ + void (* ErrorCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Error callback */ + + void (* MspInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp Init callback */ + void (* MspDeInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp DeInit callback */ + +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ +} CAN_HandleTypeDef; + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +/** + * @brief HAL CAN common Callback ID enumeration definition + */ +typedef enum +{ + HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID = 0x00U, /*!< CAN Tx Mailbox 0 complete callback ID */ + HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID = 0x01U, /*!< CAN Tx Mailbox 1 complete callback ID */ + HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID = 0x02U, /*!< CAN Tx Mailbox 2 complete callback ID */ + HAL_CAN_TX_MAILBOX0_ABORT_CB_ID = 0x03U, /*!< CAN Tx Mailbox 0 abort callback ID */ + HAL_CAN_TX_MAILBOX1_ABORT_CB_ID = 0x04U, /*!< CAN Tx Mailbox 1 abort callback ID */ + HAL_CAN_TX_MAILBOX2_ABORT_CB_ID = 0x05U, /*!< CAN Tx Mailbox 2 abort callback ID */ + HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID = 0x06U, /*!< CAN Rx FIFO 0 message pending callback ID */ + HAL_CAN_RX_FIFO0_FULL_CB_ID = 0x07U, /*!< CAN Rx FIFO 0 full callback ID */ + HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID = 0x08U, /*!< CAN Rx FIFO 1 message pending callback ID */ + HAL_CAN_RX_FIFO1_FULL_CB_ID = 0x09U, /*!< CAN Rx FIFO 1 full callback ID */ + HAL_CAN_SLEEP_CB_ID = 0x0AU, /*!< CAN Sleep callback ID */ + HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID = 0x0BU, /*!< CAN Wake Up from Rx msg callback ID */ + HAL_CAN_ERROR_CB_ID = 0x0CU, /*!< CAN Error callback ID */ + + HAL_CAN_MSPINIT_CB_ID = 0x0DU, /*!< CAN MspInit callback ID */ + HAL_CAN_MSPDEINIT_CB_ID = 0x0EU, /*!< CAN MspDeInit callback ID */ + +} HAL_CAN_CallbackIDTypeDef; + +/** + * @brief HAL CAN Callback pointer definition + */ +typedef void (*pCAN_CallbackTypeDef)(CAN_HandleTypeDef *hcan); /*!< pointer to a CAN callback function */ + +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CAN_Exported_Constants CAN Exported Constants + * @{ + */ + +/** @defgroup CAN_Error_Code CAN Error Code + * @{ + */ +#define HAL_CAN_ERROR_NONE (0x00000000U) /*!< No error */ +#define HAL_CAN_ERROR_EWG (0x00000001U) /*!< Protocol Error Warning */ +#define HAL_CAN_ERROR_EPV (0x00000002U) /*!< Error Passive */ +#define HAL_CAN_ERROR_BOF (0x00000004U) /*!< Bus-off error */ +#define HAL_CAN_ERROR_STF (0x00000008U) /*!< Stuff error */ +#define HAL_CAN_ERROR_FOR (0x00000010U) /*!< Form error */ +#define HAL_CAN_ERROR_ACK (0x00000020U) /*!< Acknowledgment error */ +#define HAL_CAN_ERROR_BR (0x00000040U) /*!< Bit recessive error */ +#define HAL_CAN_ERROR_BD (0x00000080U) /*!< Bit dominant error */ +#define HAL_CAN_ERROR_CRC (0x00000100U) /*!< CRC error */ +#define HAL_CAN_ERROR_RX_FOV0 (0x00000200U) /*!< Rx FIFO0 overrun error */ +#define HAL_CAN_ERROR_RX_FOV1 (0x00000400U) /*!< Rx FIFO1 overrun error */ +#define HAL_CAN_ERROR_TX_ALST0 (0x00000800U) /*!< TxMailbox 0 transmit failure due to arbitration lost */ +#define HAL_CAN_ERROR_TX_TERR0 (0x00001000U) /*!< TxMailbox 0 transmit failure due to transmit error */ +#define HAL_CAN_ERROR_TX_ALST1 (0x00002000U) /*!< TxMailbox 1 transmit failure due to arbitration lost */ +#define HAL_CAN_ERROR_TX_TERR1 (0x00004000U) /*!< TxMailbox 1 transmit failure due to transmit error */ +#define HAL_CAN_ERROR_TX_ALST2 (0x00008000U) /*!< TxMailbox 2 transmit failure due to arbitration lost */ +#define HAL_CAN_ERROR_TX_TERR2 (0x00010000U) /*!< TxMailbox 2 transmit failure due to transmit error */ +#define HAL_CAN_ERROR_TIMEOUT (0x00020000U) /*!< Timeout error */ +#define HAL_CAN_ERROR_NOT_INITIALIZED (0x00040000U) /*!< Peripheral not initialized */ +#define HAL_CAN_ERROR_NOT_READY (0x00080000U) /*!< Peripheral not ready */ +#define HAL_CAN_ERROR_NOT_STARTED (0x00100000U) /*!< Peripheral not started */ +#define HAL_CAN_ERROR_PARAM (0x00200000U) /*!< Parameter error */ + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +#define HAL_CAN_ERROR_INVALID_CALLBACK (0x00400000U) /*!< Invalid Callback error */ +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ +#define HAL_CAN_ERROR_INTERNAL (0x00800000U) /*!< Internal error */ + +/** + * @} + */ + +/** @defgroup CAN_InitStatus CAN InitStatus + * @{ + */ +#define CAN_INITSTATUS_FAILED (0x00000000U) /*!< CAN initialization failed */ +#define CAN_INITSTATUS_SUCCESS (0x00000001U) /*!< CAN initialization OK */ +/** + * @} + */ + +/** @defgroup CAN_operating_mode CAN Operating Mode + * @{ + */ +#define CAN_MODE_NORMAL (0x00000000U) /*!< Normal mode */ +#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ +#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ +#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ +/** + * @} + */ + + +/** @defgroup CAN_synchronisation_jump_width CAN Synchronization Jump Width + * @{ + */ +#define CAN_SJW_1TQ (0x00000000U) /*!< 1 time quantum */ +#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ +#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ +#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in Bit Segment 1 + * @{ + */ +#define CAN_BS1_1TQ (0x00000000U) /*!< 1 time quantum */ +#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ +#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ +#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ +#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ +#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ +#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ +#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ +#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ +#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ +#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ +#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ +#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ +#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ +#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ +#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in Bit Segment 2 + * @{ + */ +#define CAN_BS2_1TQ (0x00000000U) /*!< 1 time quantum */ +#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ +#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ +#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ +#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ +#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ +#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ +#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ +/** + * @} + */ + +/** @defgroup CAN_filter_mode CAN Filter Mode + * @{ + */ +#define CAN_FILTERMODE_IDMASK (0x00000000U) /*!< Identifier mask mode */ +#define CAN_FILTERMODE_IDLIST (0x00000001U) /*!< Identifier list mode */ +/** + * @} + */ + +/** @defgroup CAN_filter_scale CAN Filter Scale + * @{ + */ +#define CAN_FILTERSCALE_16BIT (0x00000000U) /*!< Two 16-bit filters */ +#define CAN_FILTERSCALE_32BIT (0x00000001U) /*!< One 32-bit filter */ +/** + * @} + */ + +/** @defgroup CAN_filter_activation CAN Filter Activation + * @{ + */ +#define CAN_FILTER_DISABLE (0x00000000U) /*!< Disable filter */ +#define CAN_FILTER_ENABLE (0x00000001U) /*!< Enable filter */ +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO CAN Filter FIFO + * @{ + */ +#define CAN_FILTER_FIFO0 (0x00000000U) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_FILTER_FIFO1 (0x00000001U) /*!< Filter FIFO 1 assignment for filter x */ +/** + * @} + */ + +/** @defgroup CAN_identifier_type CAN Identifier Type + * @{ + */ +#define CAN_ID_STD (0x00000000U) /*!< Standard Id */ +#define CAN_ID_EXT (0x00000004U) /*!< Extended Id */ +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request + * @{ + */ +#define CAN_RTR_DATA (0x00000000U) /*!< Data frame */ +#define CAN_RTR_REMOTE (0x00000002U) /*!< Remote frame */ +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number CAN Receive FIFO Number + * @{ + */ +#define CAN_RX_FIFO0 (0x00000000U) /*!< CAN receive FIFO 0 */ +#define CAN_RX_FIFO1 (0x00000001U) /*!< CAN receive FIFO 1 */ +/** + * @} + */ + +/** @defgroup CAN_Tx_Mailboxes CAN Tx Mailboxes + * @{ + */ +#define CAN_TX_MAILBOX0 (0x00000001U) /*!< Tx Mailbox 0 */ +#define CAN_TX_MAILBOX1 (0x00000002U) /*!< Tx Mailbox 1 */ +#define CAN_TX_MAILBOX2 (0x00000004U) /*!< Tx Mailbox 2 */ +/** + * @} + */ + +/** @defgroup CAN_flags CAN Flags + * @{ + */ +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 (0x00000500U) /*!< Request complete MailBox 0 flag */ +#define CAN_FLAG_TXOK0 (0x00000501U) /*!< Transmission OK MailBox 0 flag */ +#define CAN_FLAG_ALST0 (0x00000502U) /*!< Arbitration Lost MailBox 0 flag */ +#define CAN_FLAG_TERR0 (0x00000503U) /*!< Transmission error MailBox 0 flag */ +#define CAN_FLAG_RQCP1 (0x00000508U) /*!< Request complete MailBox1 flag */ +#define CAN_FLAG_TXOK1 (0x00000509U) /*!< Transmission OK MailBox 1 flag */ +#define CAN_FLAG_ALST1 (0x0000050AU) /*!< Arbitration Lost MailBox 1 flag */ +#define CAN_FLAG_TERR1 (0x0000050BU) /*!< Transmission error MailBox 1 flag */ +#define CAN_FLAG_RQCP2 (0x00000510U) /*!< Request complete MailBox2 flag */ +#define CAN_FLAG_TXOK2 (0x00000511U) /*!< Transmission OK MailBox 2 flag */ +#define CAN_FLAG_ALST2 (0x00000512U) /*!< Arbitration Lost MailBox 2 flag */ +#define CAN_FLAG_TERR2 (0x00000513U) /*!< Transmission error MailBox 2 flag */ +#define CAN_FLAG_TME0 (0x0000051AU) /*!< Transmit mailbox 0 empty flag */ +#define CAN_FLAG_TME1 (0x0000051BU) /*!< Transmit mailbox 1 empty flag */ +#define CAN_FLAG_TME2 (0x0000051CU) /*!< Transmit mailbox 2 empty flag */ +#define CAN_FLAG_LOW0 (0x0000051DU) /*!< Lowest priority mailbox 0 flag */ +#define CAN_FLAG_LOW1 (0x0000051EU) /*!< Lowest priority mailbox 1 flag */ +#define CAN_FLAG_LOW2 (0x0000051FU) /*!< Lowest priority mailbox 2 flag */ + +/* Receive Flags */ +#define CAN_FLAG_FF0 (0x00000203U) /*!< RX FIFO 0 Full flag */ +#define CAN_FLAG_FOV0 (0x00000204U) /*!< RX FIFO 0 Overrun flag */ +#define CAN_FLAG_FF1 (0x00000403U) /*!< RX FIFO 1 Full flag */ +#define CAN_FLAG_FOV1 (0x00000404U) /*!< RX FIFO 1 Overrun flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_INAK (0x00000100U) /*!< Initialization acknowledge flag */ +#define CAN_FLAG_SLAK (0x00000101U) /*!< Sleep acknowledge flag */ +#define CAN_FLAG_ERRI (0x00000102U) /*!< Error flag */ +#define CAN_FLAG_WKU (0x00000103U) /*!< Wake up interrupt flag */ +#define CAN_FLAG_SLAKI (0x00000104U) /*!< Sleep acknowledge interrupt flag */ + +/* Error Flags */ +#define CAN_FLAG_EWG (0x00000300U) /*!< Error warning flag */ +#define CAN_FLAG_EPV (0x00000301U) /*!< Error passive flag */ +#define CAN_FLAG_BOF (0x00000302U) /*!< Bus-Off flag */ +/** + * @} + */ + + +/** @defgroup CAN_Interrupts CAN Interrupts + * @{ + */ +/* Transmit Interrupt */ +#define CAN_IT_TX_MAILBOX_EMPTY ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ + +/* Receive Interrupts */ +#define CAN_IT_RX_FIFO0_MSG_PENDING ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ +#define CAN_IT_RX_FIFO0_FULL ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ +#define CAN_IT_RX_FIFO0_OVERRUN ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ +#define CAN_IT_RX_FIFO1_MSG_PENDING ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ +#define CAN_IT_RX_FIFO1_FULL ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ +#define CAN_IT_RX_FIFO1_OVERRUN ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ + +/* Operating Mode Interrupts */ +#define CAN_IT_WAKEUP ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ +#define CAN_IT_SLEEP_ACK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ + +/* Error Interrupts */ +#define CAN_IT_ERROR_WARNING ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ +#define CAN_IT_ERROR_PASSIVE ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ +#define CAN_IT_BUSOFF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ +#define CAN_IT_LAST_ERROR_CODE ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ +#define CAN_IT_ERROR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macros -----------------------------------------------------------*/ +/** @defgroup CAN_Exported_Macros CAN Exported Macros + * @{ + */ + +/** @brief Reset CAN handle state + * @param __HANDLE__ CAN handle. + * @retval None + */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) do{ \ + (__HANDLE__)->State = HAL_CAN_STATE_RESET; \ + (__HANDLE__)->MspInitCallback = NULL; \ + (__HANDLE__)->MspDeInitCallback = NULL; \ + } while(0) +#else +#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) +#endif /*USE_HAL_CAN_REGISTER_CALLBACKS */ + +/** + * @brief Enable the specified CAN interrupts. + * @param __HANDLE__ CAN handle. + * @param __INTERRUPT__ CAN Interrupt sources to enable. + * This parameter can be any combination of @arg CAN_Interrupts + * @retval None + */ +#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) + +/** + * @brief Disable the specified CAN interrupts. + * @param __HANDLE__ CAN handle. + * @param __INTERRUPT__ CAN Interrupt sources to disable. + * This parameter can be any combination of @arg CAN_Interrupts + * @retval None + */ +#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) + +/** @brief Check if the specified CAN interrupt source is enabled or disabled. + * @param __HANDLE__ specifies the CAN Handle. + * @param __INTERRUPT__ specifies the CAN interrupt source to check. + * This parameter can be a value of @arg CAN_Interrupts + * @retval The state of __IT__ (TRUE or FALSE). + */ +#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) & (__INTERRUPT__)) + +/** @brief Check whether the specified CAN flag is set or not. + * @param __HANDLE__ specifies the CAN Handle. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of @arg CAN_flags + * @retval The state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ + ((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 3U)? ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) + +/** @brief Clear the specified CAN pending flag. + * @param __HANDLE__ specifies the CAN Handle. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg CAN_FLAG_RQCP0: Request complete MailBox 0 Flag + * @arg CAN_FLAG_TXOK0: Transmission OK MailBox 0 Flag + * @arg CAN_FLAG_ALST0: Arbitration Lost MailBox 0 Flag + * @arg CAN_FLAG_TERR0: Transmission error MailBox 0 Flag + * @arg CAN_FLAG_RQCP1: Request complete MailBox 1 Flag + * @arg CAN_FLAG_TXOK1: Transmission OK MailBox 1 Flag + * @arg CAN_FLAG_ALST1: Arbitration Lost MailBox 1 Flag + * @arg CAN_FLAG_TERR1: Transmission error MailBox 1 Flag + * @arg CAN_FLAG_RQCP2: Request complete MailBox 2 Flag + * @arg CAN_FLAG_TXOK2: Transmission OK MailBox 2 Flag + * @arg CAN_FLAG_ALST2: Arbitration Lost MailBox 2 Flag + * @arg CAN_FLAG_TERR2: Transmission error MailBox 2 Flag + * @arg CAN_FLAG_FF0: RX FIFO 0 Full Flag + * @arg CAN_FLAG_FOV0: RX FIFO 0 Overrun Flag + * @arg CAN_FLAG_FF1: RX FIFO 1 Full Flag + * @arg CAN_FLAG_FOV1: RX FIFO 1 Overrun Flag + * @arg CAN_FLAG_WKUI: Wake up Interrupt Flag + * @arg CAN_FLAG_SLAKI: Sleep acknowledge Interrupt Flag + * @retval None + */ +#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ + ((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ + (((__FLAG__) >> 8U) == 1U)? (((__HANDLE__)->Instance->MSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup CAN_Exported_Functions CAN Exported Functions + * @{ + */ + +/** @addtogroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * @{ + */ + +/* Initialization and de-initialization functions *****************************/ +HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan); +void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan); +void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan); + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +/* Callbacks Register/UnRegister functions ***********************************/ +HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)); +HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID); + +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ +/** + * @} + */ + +/** @addtogroup CAN_Exported_Functions_Group2 Configuration functions + * @brief Configuration functions + * @{ + */ + +/* Configuration functions ****************************************************/ +HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig); + +/** + * @} + */ + +/** @addtogroup CAN_Exported_Functions_Group3 Control functions + * @brief Control functions + * @{ + */ + +/* Control functions **********************************************************/ +HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); +uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox); +HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); +uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan); +uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); +uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox); +HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]); +uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo); + +/** + * @} + */ + +/** @addtogroup CAN_Exported_Functions_Group4 Interrupts management + * @brief Interrupts management + * @{ + */ +/* Interrupts management ******************************************************/ +HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs); +HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs); +void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan); + +/** + * @} + */ + +/** @addtogroup CAN_Exported_Functions_Group5 Callback functions + * @brief Callback functions + * @{ + */ +/* Callbacks functions ********************************************************/ + +void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan); +void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); + +/** + * @} + */ + +/** @addtogroup CAN_Exported_Functions_Group6 Peripheral State and Error functions + * @brief CAN Peripheral State functions + * @{ + */ +/* Peripheral State and Error functions ***************************************/ +HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan); +uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); +HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan); + +/** + * @} + */ + +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/** @defgroup CAN_Private_Types CAN Private Types + * @{ + */ + +/** + * @} + */ + +/* Private variables ---------------------------------------------------------*/ +/** @defgroup CAN_Private_Variables CAN Private Variables + * @{ + */ + +/** + * @} + */ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup CAN_Private_Constants CAN Private Constants + * @{ + */ +#define CAN_FLAG_MASK (0x000000FFU) +/** + * @} + */ + +/* Private Macros -----------------------------------------------------------*/ +/** @defgroup CAN_Private_Macros CAN Private Macros + * @{ + */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ + ((MODE) == CAN_MODE_LOOPBACK)|| \ + ((MODE) == CAN_MODE_SILENT) || \ + ((MODE) == CAN_MODE_SILENT_LOOPBACK)) +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ) || \ + ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) +#define IS_CAN_BS1(BS1) (((BS1) == CAN_BS1_1TQ) || ((BS1) == CAN_BS1_2TQ) || \ + ((BS1) == CAN_BS1_3TQ) || ((BS1) == CAN_BS1_4TQ) || \ + ((BS1) == CAN_BS1_5TQ) || ((BS1) == CAN_BS1_6TQ) || \ + ((BS1) == CAN_BS1_7TQ) || ((BS1) == CAN_BS1_8TQ) || \ + ((BS1) == CAN_BS1_9TQ) || ((BS1) == CAN_BS1_10TQ)|| \ + ((BS1) == CAN_BS1_11TQ)|| ((BS1) == CAN_BS1_12TQ)|| \ + ((BS1) == CAN_BS1_13TQ)|| ((BS1) == CAN_BS1_14TQ)|| \ + ((BS1) == CAN_BS1_15TQ)|| ((BS1) == CAN_BS1_16TQ)) +#define IS_CAN_BS2(BS2) (((BS2) == CAN_BS2_1TQ) || ((BS2) == CAN_BS2_2TQ) || \ + ((BS2) == CAN_BS2_3TQ) || ((BS2) == CAN_BS2_4TQ) || \ + ((BS2) == CAN_BS2_5TQ) || ((BS2) == CAN_BS2_6TQ) || \ + ((BS2) == CAN_BS2_7TQ) || ((BS2) == CAN_BS2_8TQ)) +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) +#define IS_CAN_FILTER_ID_HALFWORD(HALFWORD) ((HALFWORD) <= 0xFFFFU) +#define IS_CAN_FILTER_BANK_DUAL(BANK) ((BANK) <= 27U) +#define IS_CAN_FILTER_BANK_SINGLE(BANK) ((BANK) <= 13U) +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ + ((MODE) == CAN_FILTERMODE_IDLIST)) +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ + ((SCALE) == CAN_FILTERSCALE_32BIT)) +#define IS_CAN_FILTER_ACTIVATION(ACTIVATION) (((ACTIVATION) == CAN_FILTER_DISABLE) || \ + ((ACTIVATION) == CAN_FILTER_ENABLE)) +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ + ((FIFO) == CAN_FILTER_FIFO1)) +#define IS_CAN_TX_MAILBOX(TRANSMITMAILBOX) (((TRANSMITMAILBOX) == CAN_TX_MAILBOX0 ) || \ + ((TRANSMITMAILBOX) == CAN_TX_MAILBOX1 ) || \ + ((TRANSMITMAILBOX) == CAN_TX_MAILBOX2 )) +#define IS_CAN_TX_MAILBOX_LIST(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= (CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2)) +#define IS_CAN_STDID(STDID) ((STDID) <= 0x7FFU) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) +#define IS_CAN_DLC(DLC) ((DLC) <= 8U) +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ + ((IDTYPE) == CAN_ID_EXT)) +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) +#define IS_CAN_RX_FIFO(FIFO) (((FIFO) == CAN_RX_FIFO0) || ((FIFO) == CAN_RX_FIFO1)) +#define IS_CAN_IT(IT) ((IT) <= (CAN_IT_TX_MAILBOX_EMPTY | CAN_IT_RX_FIFO0_MSG_PENDING | \ + CAN_IT_RX_FIFO0_FULL | CAN_IT_RX_FIFO0_OVERRUN | \ + CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_RX_FIFO1_FULL | \ + CAN_IT_RX_FIFO1_OVERRUN | CAN_IT_WAKEUP | \ + CAN_IT_SLEEP_ACK | CAN_IT_ERROR_WARNING | \ + CAN_IT_ERROR_PASSIVE | CAN_IT_BUSOFF | \ + CAN_IT_LAST_ERROR_CODE | CAN_IT_ERROR)) + +/** + * @} + */ +/* End of private macros -----------------------------------------------------*/ + +/** + * @} + */ + + +#endif /* CAN1 */ +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_HAL_CAN_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h index fdc96b5..935be05 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h @@ -1,407 +1,407 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CORTEX_H -#define __STM32F4xx_HAL_CORTEX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CORTEX - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CORTEX_Exported_Types Cortex Exported Types - * @{ - */ - -#if (__MPU_PRESENT == 1U) -/** @defgroup CORTEX_MPU_Region_Initialization_Structure_definition MPU Region Initialization Structure Definition - * @brief MPU Region initialization structure - * @{ - */ -typedef struct -{ - uint8_t Enable; /*!< Specifies the status of the region. - This parameter can be a value of @ref CORTEX_MPU_Region_Enable */ - uint8_t Number; /*!< Specifies the number of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Number */ - uint32_t BaseAddress; /*!< Specifies the base address of the region to protect. */ - uint8_t Size; /*!< Specifies the size of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Size */ - uint8_t SubRegionDisable; /*!< Specifies the number of the subregion protection to disable. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - uint8_t TypeExtField; /*!< Specifies the TEX field level. - This parameter can be a value of @ref CORTEX_MPU_TEX_Levels */ - uint8_t AccessPermission; /*!< Specifies the region access permission type. - This parameter can be a value of @ref CORTEX_MPU_Region_Permission_Attributes */ - uint8_t DisableExec; /*!< Specifies the instruction access status. - This parameter can be a value of @ref CORTEX_MPU_Instruction_Access */ - uint8_t IsShareable; /*!< Specifies the shareability status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Shareable */ - uint8_t IsCacheable; /*!< Specifies the cacheable status of the region protected. - This parameter can be a value of @ref CORTEX_MPU_Access_Cacheable */ - uint8_t IsBufferable; /*!< Specifies the bufferable status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Bufferable */ -}MPU_Region_InitTypeDef; -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CORTEX_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_Preemption_Priority_Group CORTEX Preemption Priority Group - * @{ - */ -#define NVIC_PRIORITYGROUP_0 0x00000007U /*!< 0 bits for pre-emption priority - 4 bits for subpriority */ -#define NVIC_PRIORITYGROUP_1 0x00000006U /*!< 1 bits for pre-emption priority - 3 bits for subpriority */ -#define NVIC_PRIORITYGROUP_2 0x00000005U /*!< 2 bits for pre-emption priority - 2 bits for subpriority */ -#define NVIC_PRIORITYGROUP_3 0x00000004U /*!< 3 bits for pre-emption priority - 1 bits for subpriority */ -#define NVIC_PRIORITYGROUP_4 0x00000003U /*!< 4 bits for pre-emption priority - 0 bits for subpriority */ -/** - * @} - */ - -/** @defgroup CORTEX_SysTick_clock_source CORTEX _SysTick clock source - * @{ - */ -#define SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U -#define SYSTICK_CLKSOURCE_HCLK 0x00000004U - -/** - * @} - */ - -#if (__MPU_PRESENT == 1) -/** @defgroup CORTEX_MPU_HFNMI_PRIVDEF_Control MPU HFNMI and PRIVILEGED Access control - * @{ - */ -#define MPU_HFNMI_PRIVDEF_NONE 0x00000000U -#define MPU_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk -#define MPU_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk -#define MPU_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) - -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Enable CORTEX MPU Region Enable - * @{ - */ -#define MPU_REGION_ENABLE ((uint8_t)0x01) -#define MPU_REGION_DISABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Instruction_Access CORTEX MPU Instruction Access - * @{ - */ -#define MPU_INSTRUCTION_ACCESS_ENABLE ((uint8_t)0x00) -#define MPU_INSTRUCTION_ACCESS_DISABLE ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Shareable CORTEX MPU Instruction Access Shareable - * @{ - */ -#define MPU_ACCESS_SHAREABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_SHAREABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Cacheable CORTEX MPU Instruction Access Cacheable - * @{ - */ -#define MPU_ACCESS_CACHEABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_CACHEABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Bufferable CORTEX MPU Instruction Access Bufferable - * @{ - */ -#define MPU_ACCESS_BUFFERABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_BUFFERABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_TEX_Levels MPU TEX Levels - * @{ - */ -#define MPU_TEX_LEVEL0 ((uint8_t)0x00) -#define MPU_TEX_LEVEL1 ((uint8_t)0x01) -#define MPU_TEX_LEVEL2 ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Size CORTEX MPU Region Size - * @{ - */ -#define MPU_REGION_SIZE_32B ((uint8_t)0x04) -#define MPU_REGION_SIZE_64B ((uint8_t)0x05) -#define MPU_REGION_SIZE_128B ((uint8_t)0x06) -#define MPU_REGION_SIZE_256B ((uint8_t)0x07) -#define MPU_REGION_SIZE_512B ((uint8_t)0x08) -#define MPU_REGION_SIZE_1KB ((uint8_t)0x09) -#define MPU_REGION_SIZE_2KB ((uint8_t)0x0A) -#define MPU_REGION_SIZE_4KB ((uint8_t)0x0B) -#define MPU_REGION_SIZE_8KB ((uint8_t)0x0C) -#define MPU_REGION_SIZE_16KB ((uint8_t)0x0D) -#define MPU_REGION_SIZE_32KB ((uint8_t)0x0E) -#define MPU_REGION_SIZE_64KB ((uint8_t)0x0F) -#define MPU_REGION_SIZE_128KB ((uint8_t)0x10) -#define MPU_REGION_SIZE_256KB ((uint8_t)0x11) -#define MPU_REGION_SIZE_512KB ((uint8_t)0x12) -#define MPU_REGION_SIZE_1MB ((uint8_t)0x13) -#define MPU_REGION_SIZE_2MB ((uint8_t)0x14) -#define MPU_REGION_SIZE_4MB ((uint8_t)0x15) -#define MPU_REGION_SIZE_8MB ((uint8_t)0x16) -#define MPU_REGION_SIZE_16MB ((uint8_t)0x17) -#define MPU_REGION_SIZE_32MB ((uint8_t)0x18) -#define MPU_REGION_SIZE_64MB ((uint8_t)0x19) -#define MPU_REGION_SIZE_128MB ((uint8_t)0x1A) -#define MPU_REGION_SIZE_256MB ((uint8_t)0x1B) -#define MPU_REGION_SIZE_512MB ((uint8_t)0x1C) -#define MPU_REGION_SIZE_1GB ((uint8_t)0x1D) -#define MPU_REGION_SIZE_2GB ((uint8_t)0x1E) -#define MPU_REGION_SIZE_4GB ((uint8_t)0x1F) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Permission_Attributes CORTEX MPU Region Permission Attributes - * @{ - */ -#define MPU_REGION_NO_ACCESS ((uint8_t)0x00) -#define MPU_REGION_PRIV_RW ((uint8_t)0x01) -#define MPU_REGION_PRIV_RW_URO ((uint8_t)0x02) -#define MPU_REGION_FULL_ACCESS ((uint8_t)0x03) -#define MPU_REGION_PRIV_RO ((uint8_t)0x05) -#define MPU_REGION_PRIV_RO_URO ((uint8_t)0x06) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Number CORTEX MPU Region Number - * @{ - */ -#define MPU_REGION_NUMBER0 ((uint8_t)0x00) -#define MPU_REGION_NUMBER1 ((uint8_t)0x01) -#define MPU_REGION_NUMBER2 ((uint8_t)0x02) -#define MPU_REGION_NUMBER3 ((uint8_t)0x03) -#define MPU_REGION_NUMBER4 ((uint8_t)0x04) -#define MPU_REGION_NUMBER5 ((uint8_t)0x05) -#define MPU_REGION_NUMBER6 ((uint8_t)0x06) -#define MPU_REGION_NUMBER7 ((uint8_t)0x07) -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - - -/* Exported Macros -----------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CORTEX_Exported_Functions - * @{ - */ - -/** @addtogroup CORTEX_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup); -void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority); -void HAL_NVIC_EnableIRQ(IRQn_Type IRQn); -void HAL_NVIC_DisableIRQ(IRQn_Type IRQn); -void HAL_NVIC_SystemReset(void); -uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb); -/** - * @} - */ - -/** @addtogroup CORTEX_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -uint32_t HAL_NVIC_GetPriorityGrouping(void); -void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority); -uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn); -uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn); -void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource); -void HAL_SYSTICK_IRQHandler(void); -void HAL_SYSTICK_Callback(void); - -#if (__MPU_PRESENT == 1U) -void HAL_MPU_Enable(uint32_t MPU_Control); -void HAL_MPU_Disable(void); -void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init); -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CORTEX_Private_Macros CORTEX Private Macros - * @{ - */ -#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PRIORITYGROUP_0) || \ - ((GROUP) == NVIC_PRIORITYGROUP_1) || \ - ((GROUP) == NVIC_PRIORITYGROUP_2) || \ - ((GROUP) == NVIC_PRIORITYGROUP_3) || \ - ((GROUP) == NVIC_PRIORITYGROUP_4)) - -#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_DEVICE_IRQ(IRQ) ((IRQ) >= (IRQn_Type)0x00U) - -#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \ - ((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8)) - -#if (__MPU_PRESENT == 1U) -#define IS_MPU_REGION_ENABLE(STATE) (((STATE) == MPU_REGION_ENABLE) || \ - ((STATE) == MPU_REGION_DISABLE)) - -#define IS_MPU_INSTRUCTION_ACCESS(STATE) (((STATE) == MPU_INSTRUCTION_ACCESS_ENABLE) || \ - ((STATE) == MPU_INSTRUCTION_ACCESS_DISABLE)) - -#define IS_MPU_ACCESS_SHAREABLE(STATE) (((STATE) == MPU_ACCESS_SHAREABLE) || \ - ((STATE) == MPU_ACCESS_NOT_SHAREABLE)) - -#define IS_MPU_ACCESS_CACHEABLE(STATE) (((STATE) == MPU_ACCESS_CACHEABLE) || \ - ((STATE) == MPU_ACCESS_NOT_CACHEABLE)) - -#define IS_MPU_ACCESS_BUFFERABLE(STATE) (((STATE) == MPU_ACCESS_BUFFERABLE) || \ - ((STATE) == MPU_ACCESS_NOT_BUFFERABLE)) - -#define IS_MPU_TEX_LEVEL(TYPE) (((TYPE) == MPU_TEX_LEVEL0) || \ - ((TYPE) == MPU_TEX_LEVEL1) || \ - ((TYPE) == MPU_TEX_LEVEL2)) - -#define IS_MPU_REGION_PERMISSION_ATTRIBUTE(TYPE) (((TYPE) == MPU_REGION_NO_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RW) || \ - ((TYPE) == MPU_REGION_PRIV_RW_URO) || \ - ((TYPE) == MPU_REGION_FULL_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RO) || \ - ((TYPE) == MPU_REGION_PRIV_RO_URO)) - -#define IS_MPU_REGION_NUMBER(NUMBER) (((NUMBER) == MPU_REGION_NUMBER0) || \ - ((NUMBER) == MPU_REGION_NUMBER1) || \ - ((NUMBER) == MPU_REGION_NUMBER2) || \ - ((NUMBER) == MPU_REGION_NUMBER3) || \ - ((NUMBER) == MPU_REGION_NUMBER4) || \ - ((NUMBER) == MPU_REGION_NUMBER5) || \ - ((NUMBER) == MPU_REGION_NUMBER6) || \ - ((NUMBER) == MPU_REGION_NUMBER7)) - -#define IS_MPU_REGION_SIZE(SIZE) (((SIZE) == MPU_REGION_SIZE_32B) || \ - ((SIZE) == MPU_REGION_SIZE_64B) || \ - ((SIZE) == MPU_REGION_SIZE_128B) || \ - ((SIZE) == MPU_REGION_SIZE_256B) || \ - ((SIZE) == MPU_REGION_SIZE_512B) || \ - ((SIZE) == MPU_REGION_SIZE_1KB) || \ - ((SIZE) == MPU_REGION_SIZE_2KB) || \ - ((SIZE) == MPU_REGION_SIZE_4KB) || \ - ((SIZE) == MPU_REGION_SIZE_8KB) || \ - ((SIZE) == MPU_REGION_SIZE_16KB) || \ - ((SIZE) == MPU_REGION_SIZE_32KB) || \ - ((SIZE) == MPU_REGION_SIZE_64KB) || \ - ((SIZE) == MPU_REGION_SIZE_128KB) || \ - ((SIZE) == MPU_REGION_SIZE_256KB) || \ - ((SIZE) == MPU_REGION_SIZE_512KB) || \ - ((SIZE) == MPU_REGION_SIZE_1MB) || \ - ((SIZE) == MPU_REGION_SIZE_2MB) || \ - ((SIZE) == MPU_REGION_SIZE_4MB) || \ - ((SIZE) == MPU_REGION_SIZE_8MB) || \ - ((SIZE) == MPU_REGION_SIZE_16MB) || \ - ((SIZE) == MPU_REGION_SIZE_32MB) || \ - ((SIZE) == MPU_REGION_SIZE_64MB) || \ - ((SIZE) == MPU_REGION_SIZE_128MB) || \ - ((SIZE) == MPU_REGION_SIZE_256MB) || \ - ((SIZE) == MPU_REGION_SIZE_512MB) || \ - ((SIZE) == MPU_REGION_SIZE_1GB) || \ - ((SIZE) == MPU_REGION_SIZE_2GB) || \ - ((SIZE) == MPU_REGION_SIZE_4GB)) - -#define IS_MPU_SUB_REGION_DISABLE(SUBREGION) ((SUBREGION) < (uint16_t)0x00FF) -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CORTEX_H */ - - +/** + ****************************************************************************** + * @file stm32f4xx_hal_cortex.h + * @author MCD Application Team + * @brief Header file of CORTEX HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CORTEX_H +#define __STM32F4xx_HAL_CORTEX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup CORTEX + * @{ + */ +/* Exported types ------------------------------------------------------------*/ +/** @defgroup CORTEX_Exported_Types Cortex Exported Types + * @{ + */ + +#if (__MPU_PRESENT == 1U) +/** @defgroup CORTEX_MPU_Region_Initialization_Structure_definition MPU Region Initialization Structure Definition + * @brief MPU Region initialization structure + * @{ + */ +typedef struct +{ + uint8_t Enable; /*!< Specifies the status of the region. + This parameter can be a value of @ref CORTEX_MPU_Region_Enable */ + uint8_t Number; /*!< Specifies the number of the region to protect. + This parameter can be a value of @ref CORTEX_MPU_Region_Number */ + uint32_t BaseAddress; /*!< Specifies the base address of the region to protect. */ + uint8_t Size; /*!< Specifies the size of the region to protect. + This parameter can be a value of @ref CORTEX_MPU_Region_Size */ + uint8_t SubRegionDisable; /*!< Specifies the number of the subregion protection to disable. + This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */ + uint8_t TypeExtField; /*!< Specifies the TEX field level. + This parameter can be a value of @ref CORTEX_MPU_TEX_Levels */ + uint8_t AccessPermission; /*!< Specifies the region access permission type. + This parameter can be a value of @ref CORTEX_MPU_Region_Permission_Attributes */ + uint8_t DisableExec; /*!< Specifies the instruction access status. + This parameter can be a value of @ref CORTEX_MPU_Instruction_Access */ + uint8_t IsShareable; /*!< Specifies the shareability status of the protected region. + This parameter can be a value of @ref CORTEX_MPU_Access_Shareable */ + uint8_t IsCacheable; /*!< Specifies the cacheable status of the region protected. + This parameter can be a value of @ref CORTEX_MPU_Access_Cacheable */ + uint8_t IsBufferable; /*!< Specifies the bufferable status of the protected region. + This parameter can be a value of @ref CORTEX_MPU_Access_Bufferable */ +}MPU_Region_InitTypeDef; +/** + * @} + */ +#endif /* __MPU_PRESENT */ + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CORTEX_Exported_Constants CORTEX Exported Constants + * @{ + */ + +/** @defgroup CORTEX_Preemption_Priority_Group CORTEX Preemption Priority Group + * @{ + */ +#define NVIC_PRIORITYGROUP_0 0x00000007U /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PRIORITYGROUP_1 0x00000006U /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PRIORITYGROUP_2 0x00000005U /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PRIORITYGROUP_3 0x00000004U /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PRIORITYGROUP_4 0x00000003U /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ +/** + * @} + */ + +/** @defgroup CORTEX_SysTick_clock_source CORTEX _SysTick clock source + * @{ + */ +#define SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U +#define SYSTICK_CLKSOURCE_HCLK 0x00000004U + +/** + * @} + */ + +#if (__MPU_PRESENT == 1) +/** @defgroup CORTEX_MPU_HFNMI_PRIVDEF_Control MPU HFNMI and PRIVILEGED Access control + * @{ + */ +#define MPU_HFNMI_PRIVDEF_NONE 0x00000000U +#define MPU_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk +#define MPU_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk +#define MPU_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) + +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Region_Enable CORTEX MPU Region Enable + * @{ + */ +#define MPU_REGION_ENABLE ((uint8_t)0x01) +#define MPU_REGION_DISABLE ((uint8_t)0x00) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Instruction_Access CORTEX MPU Instruction Access + * @{ + */ +#define MPU_INSTRUCTION_ACCESS_ENABLE ((uint8_t)0x00) +#define MPU_INSTRUCTION_ACCESS_DISABLE ((uint8_t)0x01) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Access_Shareable CORTEX MPU Instruction Access Shareable + * @{ + */ +#define MPU_ACCESS_SHAREABLE ((uint8_t)0x01) +#define MPU_ACCESS_NOT_SHAREABLE ((uint8_t)0x00) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Access_Cacheable CORTEX MPU Instruction Access Cacheable + * @{ + */ +#define MPU_ACCESS_CACHEABLE ((uint8_t)0x01) +#define MPU_ACCESS_NOT_CACHEABLE ((uint8_t)0x00) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Access_Bufferable CORTEX MPU Instruction Access Bufferable + * @{ + */ +#define MPU_ACCESS_BUFFERABLE ((uint8_t)0x01) +#define MPU_ACCESS_NOT_BUFFERABLE ((uint8_t)0x00) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_TEX_Levels MPU TEX Levels + * @{ + */ +#define MPU_TEX_LEVEL0 ((uint8_t)0x00) +#define MPU_TEX_LEVEL1 ((uint8_t)0x01) +#define MPU_TEX_LEVEL2 ((uint8_t)0x02) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Region_Size CORTEX MPU Region Size + * @{ + */ +#define MPU_REGION_SIZE_32B ((uint8_t)0x04) +#define MPU_REGION_SIZE_64B ((uint8_t)0x05) +#define MPU_REGION_SIZE_128B ((uint8_t)0x06) +#define MPU_REGION_SIZE_256B ((uint8_t)0x07) +#define MPU_REGION_SIZE_512B ((uint8_t)0x08) +#define MPU_REGION_SIZE_1KB ((uint8_t)0x09) +#define MPU_REGION_SIZE_2KB ((uint8_t)0x0A) +#define MPU_REGION_SIZE_4KB ((uint8_t)0x0B) +#define MPU_REGION_SIZE_8KB ((uint8_t)0x0C) +#define MPU_REGION_SIZE_16KB ((uint8_t)0x0D) +#define MPU_REGION_SIZE_32KB ((uint8_t)0x0E) +#define MPU_REGION_SIZE_64KB ((uint8_t)0x0F) +#define MPU_REGION_SIZE_128KB ((uint8_t)0x10) +#define MPU_REGION_SIZE_256KB ((uint8_t)0x11) +#define MPU_REGION_SIZE_512KB ((uint8_t)0x12) +#define MPU_REGION_SIZE_1MB ((uint8_t)0x13) +#define MPU_REGION_SIZE_2MB ((uint8_t)0x14) +#define MPU_REGION_SIZE_4MB ((uint8_t)0x15) +#define MPU_REGION_SIZE_8MB ((uint8_t)0x16) +#define MPU_REGION_SIZE_16MB ((uint8_t)0x17) +#define MPU_REGION_SIZE_32MB ((uint8_t)0x18) +#define MPU_REGION_SIZE_64MB ((uint8_t)0x19) +#define MPU_REGION_SIZE_128MB ((uint8_t)0x1A) +#define MPU_REGION_SIZE_256MB ((uint8_t)0x1B) +#define MPU_REGION_SIZE_512MB ((uint8_t)0x1C) +#define MPU_REGION_SIZE_1GB ((uint8_t)0x1D) +#define MPU_REGION_SIZE_2GB ((uint8_t)0x1E) +#define MPU_REGION_SIZE_4GB ((uint8_t)0x1F) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Region_Permission_Attributes CORTEX MPU Region Permission Attributes + * @{ + */ +#define MPU_REGION_NO_ACCESS ((uint8_t)0x00) +#define MPU_REGION_PRIV_RW ((uint8_t)0x01) +#define MPU_REGION_PRIV_RW_URO ((uint8_t)0x02) +#define MPU_REGION_FULL_ACCESS ((uint8_t)0x03) +#define MPU_REGION_PRIV_RO ((uint8_t)0x05) +#define MPU_REGION_PRIV_RO_URO ((uint8_t)0x06) +/** + * @} + */ + +/** @defgroup CORTEX_MPU_Region_Number CORTEX MPU Region Number + * @{ + */ +#define MPU_REGION_NUMBER0 ((uint8_t)0x00) +#define MPU_REGION_NUMBER1 ((uint8_t)0x01) +#define MPU_REGION_NUMBER2 ((uint8_t)0x02) +#define MPU_REGION_NUMBER3 ((uint8_t)0x03) +#define MPU_REGION_NUMBER4 ((uint8_t)0x04) +#define MPU_REGION_NUMBER5 ((uint8_t)0x05) +#define MPU_REGION_NUMBER6 ((uint8_t)0x06) +#define MPU_REGION_NUMBER7 ((uint8_t)0x07) +/** + * @} + */ +#endif /* __MPU_PRESENT */ + +/** + * @} + */ + + +/* Exported Macros -----------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup CORTEX_Exported_Functions + * @{ + */ + +/** @addtogroup CORTEX_Exported_Functions_Group1 + * @{ + */ +/* Initialization and de-initialization functions *****************************/ +void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup); +void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority); +void HAL_NVIC_EnableIRQ(IRQn_Type IRQn); +void HAL_NVIC_DisableIRQ(IRQn_Type IRQn); +void HAL_NVIC_SystemReset(void); +uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb); +/** + * @} + */ + +/** @addtogroup CORTEX_Exported_Functions_Group2 + * @{ + */ +/* Peripheral Control functions ***********************************************/ +uint32_t HAL_NVIC_GetPriorityGrouping(void); +void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority); +uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn); +void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn); +void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn); +uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn); +void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource); +void HAL_SYSTICK_IRQHandler(void); +void HAL_SYSTICK_Callback(void); + +#if (__MPU_PRESENT == 1U) +void HAL_MPU_Enable(uint32_t MPU_Control); +void HAL_MPU_Disable(void); +void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init); +#endif /* __MPU_PRESENT */ +/** + * @} + */ + +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @defgroup CORTEX_Private_Macros CORTEX Private Macros + * @{ + */ +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PRIORITYGROUP_0) || \ + ((GROUP) == NVIC_PRIORITYGROUP_1) || \ + ((GROUP) == NVIC_PRIORITYGROUP_2) || \ + ((GROUP) == NVIC_PRIORITYGROUP_3) || \ + ((GROUP) == NVIC_PRIORITYGROUP_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) + +#define IS_NVIC_DEVICE_IRQ(IRQ) ((IRQ) >= (IRQn_Type)0x00U) + +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \ + ((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8)) + +#if (__MPU_PRESENT == 1U) +#define IS_MPU_REGION_ENABLE(STATE) (((STATE) == MPU_REGION_ENABLE) || \ + ((STATE) == MPU_REGION_DISABLE)) + +#define IS_MPU_INSTRUCTION_ACCESS(STATE) (((STATE) == MPU_INSTRUCTION_ACCESS_ENABLE) || \ + ((STATE) == MPU_INSTRUCTION_ACCESS_DISABLE)) + +#define IS_MPU_ACCESS_SHAREABLE(STATE) (((STATE) == MPU_ACCESS_SHAREABLE) || \ + ((STATE) == MPU_ACCESS_NOT_SHAREABLE)) + +#define IS_MPU_ACCESS_CACHEABLE(STATE) (((STATE) == MPU_ACCESS_CACHEABLE) || \ + ((STATE) == MPU_ACCESS_NOT_CACHEABLE)) + +#define IS_MPU_ACCESS_BUFFERABLE(STATE) (((STATE) == MPU_ACCESS_BUFFERABLE) || \ + ((STATE) == MPU_ACCESS_NOT_BUFFERABLE)) + +#define IS_MPU_TEX_LEVEL(TYPE) (((TYPE) == MPU_TEX_LEVEL0) || \ + ((TYPE) == MPU_TEX_LEVEL1) || \ + ((TYPE) == MPU_TEX_LEVEL2)) + +#define IS_MPU_REGION_PERMISSION_ATTRIBUTE(TYPE) (((TYPE) == MPU_REGION_NO_ACCESS) || \ + ((TYPE) == MPU_REGION_PRIV_RW) || \ + ((TYPE) == MPU_REGION_PRIV_RW_URO) || \ + ((TYPE) == MPU_REGION_FULL_ACCESS) || \ + ((TYPE) == MPU_REGION_PRIV_RO) || \ + ((TYPE) == MPU_REGION_PRIV_RO_URO)) + +#define IS_MPU_REGION_NUMBER(NUMBER) (((NUMBER) == MPU_REGION_NUMBER0) || \ + ((NUMBER) == MPU_REGION_NUMBER1) || \ + ((NUMBER) == MPU_REGION_NUMBER2) || \ + ((NUMBER) == MPU_REGION_NUMBER3) || \ + ((NUMBER) == MPU_REGION_NUMBER4) || \ + ((NUMBER) == MPU_REGION_NUMBER5) || \ + ((NUMBER) == MPU_REGION_NUMBER6) || \ + ((NUMBER) == MPU_REGION_NUMBER7)) + +#define IS_MPU_REGION_SIZE(SIZE) (((SIZE) == MPU_REGION_SIZE_32B) || \ + ((SIZE) == MPU_REGION_SIZE_64B) || \ + ((SIZE) == MPU_REGION_SIZE_128B) || \ + ((SIZE) == MPU_REGION_SIZE_256B) || \ + ((SIZE) == MPU_REGION_SIZE_512B) || \ + ((SIZE) == MPU_REGION_SIZE_1KB) || \ + ((SIZE) == MPU_REGION_SIZE_2KB) || \ + ((SIZE) == MPU_REGION_SIZE_4KB) || \ + ((SIZE) == MPU_REGION_SIZE_8KB) || \ + ((SIZE) == MPU_REGION_SIZE_16KB) || \ + ((SIZE) == MPU_REGION_SIZE_32KB) || \ + ((SIZE) == MPU_REGION_SIZE_64KB) || \ + ((SIZE) == MPU_REGION_SIZE_128KB) || \ + ((SIZE) == MPU_REGION_SIZE_256KB) || \ + ((SIZE) == MPU_REGION_SIZE_512KB) || \ + ((SIZE) == MPU_REGION_SIZE_1MB) || \ + ((SIZE) == MPU_REGION_SIZE_2MB) || \ + ((SIZE) == MPU_REGION_SIZE_4MB) || \ + ((SIZE) == MPU_REGION_SIZE_8MB) || \ + ((SIZE) == MPU_REGION_SIZE_16MB) || \ + ((SIZE) == MPU_REGION_SIZE_32MB) || \ + ((SIZE) == MPU_REGION_SIZE_64MB) || \ + ((SIZE) == MPU_REGION_SIZE_128MB) || \ + ((SIZE) == MPU_REGION_SIZE_256MB) || \ + ((SIZE) == MPU_REGION_SIZE_512MB) || \ + ((SIZE) == MPU_REGION_SIZE_1GB) || \ + ((SIZE) == MPU_REGION_SIZE_2GB) || \ + ((SIZE) == MPU_REGION_SIZE_4GB)) + +#define IS_MPU_SUB_REGION_DISABLE(SUBREGION) ((SUBREGION) < (uint16_t)0x00FF) +#endif /* __MPU_PRESENT */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CORTEX_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h index f9bbec2..094b411 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h @@ -1,210 +1,210 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_def.h - * @author MCD Application Team - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DEF -#define __STM32F4xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" -#include "Legacy/stm32_hal_legacy.h" -#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ - -#define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ - -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0U) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__ specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1U) - /* Reserved for future use */ - #error "USE_RTOS should be 0 in the current HAL release" -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0U) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0U) -#endif /* USE_RTOS */ - -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif - #ifndef __packed - #define __packed __attribute__((packed)) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __ALIGN_END -#define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler V5*/ -#define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) -/* ARM Compiler V4/V5 and V6 - -------------------------- - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) -/* ARM V4/V5 and V6 & GNU Compiler - ------------------------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F4xx_HAL_DEF */ - - +/** + ****************************************************************************** + * @file stm32f4xx_hal_def.h + * @author MCD Application Team + * @brief This file contains HAL common defines, enumeration, macros and + * structures definitions. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_DEF +#define __STM32F4xx_HAL_DEF + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" +#include "Legacy/stm32_hal_legacy.h" +#include + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief HAL Status structures definition + */ +typedef enum +{ + HAL_OK = 0x00U, + HAL_ERROR = 0x01U, + HAL_BUSY = 0x02U, + HAL_TIMEOUT = 0x03U +} HAL_StatusTypeDef; + +/** + * @brief HAL Lock structures definition + */ +typedef enum +{ + HAL_UNLOCKED = 0x00U, + HAL_LOCKED = 0x01U +} HAL_LockTypeDef; + +/* Exported macro ------------------------------------------------------------*/ + +#define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ + +#define HAL_MAX_DELAY 0xFFFFFFFFU + +#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) +#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) + +#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ + do{ \ + (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ + (__DMA_HANDLE__).Parent = (__HANDLE__); \ + } while(0U) + +/** @brief Reset the Handle's State field. + * @param __HANDLE__ specifies the Peripheral Handle. + * @note This macro can be used for the following purpose: + * - When the Handle is declared as local variable; before passing it as parameter + * to HAL_PPP_Init() for the first time, it is mandatory to use this macro + * to set to 0 the Handle's "State" field. + * Otherwise, "State" field may have any random value and the first time the function + * HAL_PPP_Init() is called, the low level hardware initialization will be missed + * (i.e. HAL_PPP_MspInit() will not be executed). + * - When there is a need to reconfigure the low level hardware: instead of calling + * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). + * In this later function, when the Handle's "State" field is set to 0, it will execute the function + * HAL_PPP_MspInit() which will reconfigure the low level hardware. + * @retval None + */ +#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) + +#if (USE_RTOS == 1U) + /* Reserved for future use */ + #error "USE_RTOS should be 0 in the current HAL release" +#else + #define __HAL_LOCK(__HANDLE__) \ + do{ \ + if((__HANDLE__)->Lock == HAL_LOCKED) \ + { \ + return HAL_BUSY; \ + } \ + else \ + { \ + (__HANDLE__)->Lock = HAL_LOCKED; \ + } \ + }while (0U) + + #define __HAL_UNLOCK(__HANDLE__) \ + do{ \ + (__HANDLE__)->Lock = HAL_UNLOCKED; \ + }while (0U) +#endif /* USE_RTOS */ + +#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ + #ifndef __weak + #define __weak __attribute__((weak)) + #endif + #ifndef __packed + #define __packed __attribute__((packed)) + #endif +#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ + #ifndef __weak + #define __weak __attribute__((weak)) + #endif /* __weak */ + #ifndef __packed + #define __packed __attribute__((__packed__)) + #endif /* __packed */ +#endif /* __GNUC__ */ + + +/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ +#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ + #ifndef __ALIGN_BEGIN + #define __ALIGN_BEGIN + #endif + #ifndef __ALIGN_END + #define __ALIGN_END __attribute__ ((aligned (4))) + #endif +#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ + #ifndef __ALIGN_END +#define __ALIGN_END __attribute__ ((aligned (4))) + #endif /* __ALIGN_END */ + #ifndef __ALIGN_BEGIN + #define __ALIGN_BEGIN + #endif /* __ALIGN_BEGIN */ +#else + #ifndef __ALIGN_END + #define __ALIGN_END + #endif /* __ALIGN_END */ + #ifndef __ALIGN_BEGIN + #if defined (__CC_ARM) /* ARM Compiler V5*/ +#define __ALIGN_BEGIN __align(4) + #elif defined (__ICCARM__) /* IAR Compiler */ + #define __ALIGN_BEGIN + #endif /* __CC_ARM */ + #endif /* __ALIGN_BEGIN */ +#endif /* __GNUC__ */ + + +/** + * @brief __RAM_FUNC definition + */ +#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) +/* ARM Compiler V4/V5 and V6 + -------------------------- + RAM functions are defined using the toolchain options. + Functions that are executed in RAM should reside in a separate source module. + Using the 'Options for File' dialog you can simply change the 'Code / Const' + area of a module to a memory space in physical RAM. + Available memory areas are declared in the 'Target' tab of the 'Options for Target' + dialog. +*/ +#define __RAM_FUNC + +#elif defined ( __ICCARM__ ) +/* ICCARM Compiler + --------------- + RAM functions are defined using a specific toolchain keyword "__ramfunc". +*/ +#define __RAM_FUNC __ramfunc + +#elif defined ( __GNUC__ ) +/* GNU Compiler + ------------ + RAM functions are defined using a specific toolchain attribute + "__attribute__((section(".RamFunc")))". +*/ +#define __RAM_FUNC __attribute__((section(".RamFunc"))) + +#endif + +/** + * @brief __NOINLINE definition + */ +#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) +/* ARM V4/V5 and V6 & GNU Compiler + ------------------------------- +*/ +#define __NOINLINE __attribute__ ( (noinline) ) + +#elif defined ( __ICCARM__ ) +/* ICCARM Compiler + --------------- +*/ +#define __NOINLINE _Pragma("optimize = no_inline") + +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* ___STM32F4xx_HAL_DEF */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h index 7ff3836..336b2bb 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h @@ -1,802 +1,802 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma.h - * @author MCD Application Team - * @brief Header file of DMA HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_H -#define __STM32F4xx_HAL_DMA_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMA - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Types DMA Exported Types - * @brief DMA Exported Types - * @{ - */ - -/** - * @brief DMA Configuration Structure definition - */ -typedef struct -{ - uint32_t Channel; /*!< Specifies the channel used for the specified stream. - This parameter can be a value of @ref DMA_Channel_selection */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_Data_transfer_direction */ - - uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not. - This parameter can be a value of @ref DMA_Peripheral_incremented_mode */ - - uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not. - This parameter can be a value of @ref DMA_Memory_incremented_mode */ - - uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width. - This parameter can be a value of @ref DMA_Peripheral_data_size */ - - uint32_t MemDataAlignment; /*!< Specifies the Memory data width. - This parameter can be a value of @ref DMA_Memory_data_size */ - - uint32_t Mode; /*!< Specifies the operation mode of the DMAy Streamx. - This parameter can be a value of @ref DMA_mode - @note The circular buffer mode cannot be used if the memory-to-memory - data transfer is configured on the selected Stream */ - - uint32_t Priority; /*!< Specifies the software priority for the DMAy Streamx. - This parameter can be a value of @ref DMA_Priority_level */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_FIFO_direct_mode - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_FIFO_threshold_level */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Memory_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Peripheral_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ -}DMA_InitTypeDef; - - -/** - * @brief HAL DMA State structures definition - */ -typedef enum -{ - HAL_DMA_STATE_RESET = 0x00U, /*!< DMA not yet initialized or disabled */ - HAL_DMA_STATE_READY = 0x01U, /*!< DMA initialized and ready for use */ - HAL_DMA_STATE_BUSY = 0x02U, /*!< DMA process is ongoing */ - HAL_DMA_STATE_TIMEOUT = 0x03U, /*!< DMA timeout state */ - HAL_DMA_STATE_ERROR = 0x04U, /*!< DMA error state */ - HAL_DMA_STATE_ABORT = 0x05U, /*!< DMA Abort state */ -}HAL_DMA_StateTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_FULL_TRANSFER = 0x00U, /*!< Full transfer */ - HAL_DMA_HALF_TRANSFER = 0x01U /*!< Half Transfer */ -}HAL_DMA_LevelCompleteTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_XFER_CPLT_CB_ID = 0x00U, /*!< Full transfer */ - HAL_DMA_XFER_HALFCPLT_CB_ID = 0x01U, /*!< Half Transfer */ - HAL_DMA_XFER_M1CPLT_CB_ID = 0x02U, /*!< M1 Full Transfer */ - HAL_DMA_XFER_M1HALFCPLT_CB_ID = 0x03U, /*!< M1 Half Transfer */ - HAL_DMA_XFER_ERROR_CB_ID = 0x04U, /*!< Error */ - HAL_DMA_XFER_ABORT_CB_ID = 0x05U, /*!< Abort */ - HAL_DMA_XFER_ALL_CB_ID = 0x06U /*!< All */ -}HAL_DMA_CallbackIDTypeDef; - -/** - * @brief DMA handle Structure definition - */ -typedef struct __DMA_HandleTypeDef -{ - DMA_Stream_TypeDef *Instance; /*!< Register base address */ - - DMA_InitTypeDef Init; /*!< DMA communication parameters */ - - HAL_LockTypeDef Lock; /*!< DMA locking object */ - - __IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */ - - void *Parent; /*!< Parent object state */ - - void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */ - - void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */ - - void (* XferM1CpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete Memory1 callback */ - - void (* XferM1HalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Half complete Memory1 callback */ - - void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */ - - void (* XferAbortCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Abort callback */ - - __IO uint32_t ErrorCode; /*!< DMA Error code */ - - uint32_t StreamBaseAddress; /*!< DMA Stream Base Address */ - - uint32_t StreamIndex; /*!< DMA Stream Index */ - -}DMA_HandleTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Constants DMA Exported Constants - * @brief DMA Exported constants - * @{ - */ - -/** @defgroup DMA_Error_Code DMA Error Code - * @brief DMA Error Code - * @{ - */ -#define HAL_DMA_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DMA_ERROR_TE 0x00000001U /*!< Transfer error */ -#define HAL_DMA_ERROR_FE 0x00000002U /*!< FIFO error */ -#define HAL_DMA_ERROR_DME 0x00000004U /*!< Direct Mode error */ -#define HAL_DMA_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#define HAL_DMA_ERROR_PARAM 0x00000040U /*!< Parameter error */ -#define HAL_DMA_ERROR_NO_XFER 0x00000080U /*!< Abort requested with no Xfer ongoing */ -#define HAL_DMA_ERROR_NOT_SUPPORTED 0x00000100U /*!< Not supported mode */ -/** - * @} - */ - -/** @defgroup DMA_Channel_selection DMA Channel selection - * @brief DMA channel selection - * @{ - */ -#define DMA_CHANNEL_0 0x00000000U /*!< DMA Channel 0 */ -#define DMA_CHANNEL_1 0x02000000U /*!< DMA Channel 1 */ -#define DMA_CHANNEL_2 0x04000000U /*!< DMA Channel 2 */ -#define DMA_CHANNEL_3 0x06000000U /*!< DMA Channel 3 */ -#define DMA_CHANNEL_4 0x08000000U /*!< DMA Channel 4 */ -#define DMA_CHANNEL_5 0x0A000000U /*!< DMA Channel 5 */ -#define DMA_CHANNEL_6 0x0C000000U /*!< DMA Channel 6 */ -#define DMA_CHANNEL_7 0x0E000000U /*!< DMA Channel 7 */ -#if defined (DMA_SxCR_CHSEL_3) -#define DMA_CHANNEL_8 0x10000000U /*!< DMA Channel 8 */ -#define DMA_CHANNEL_9 0x12000000U /*!< DMA Channel 9 */ -#define DMA_CHANNEL_10 0x14000000U /*!< DMA Channel 10 */ -#define DMA_CHANNEL_11 0x16000000U /*!< DMA Channel 11 */ -#define DMA_CHANNEL_12 0x18000000U /*!< DMA Channel 12 */ -#define DMA_CHANNEL_13 0x1A000000U /*!< DMA Channel 13 */ -#define DMA_CHANNEL_14 0x1C000000U /*!< DMA Channel 14 */ -#define DMA_CHANNEL_15 0x1E000000U /*!< DMA Channel 15 */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_Data_transfer_direction DMA Data transfer direction - * @brief DMA data transfer direction - * @{ - */ -#define DMA_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_SxCR_DIR_0) /*!< Memory to peripheral direction */ -#define DMA_MEMORY_TO_MEMORY ((uint32_t)DMA_SxCR_DIR_1) /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_incremented_mode DMA Peripheral incremented mode - * @brief DMA peripheral incremented mode - * @{ - */ -#define DMA_PINC_ENABLE ((uint32_t)DMA_SxCR_PINC) /*!< Peripheral increment mode enable */ -#define DMA_PINC_DISABLE 0x00000000U /*!< Peripheral increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Memory_incremented_mode DMA Memory incremented mode - * @brief DMA memory incremented mode - * @{ - */ -#define DMA_MINC_ENABLE ((uint32_t)DMA_SxCR_MINC) /*!< Memory increment mode enable */ -#define DMA_MINC_DISABLE 0x00000000U /*!< Memory increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_data_size DMA Peripheral data size - * @brief DMA peripheral data size - * @{ - */ -#define DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment: Byte */ -#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_PSIZE_0) /*!< Peripheral data alignment: HalfWord */ -#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_SxCR_PSIZE_1) /*!< Peripheral data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_Memory_data_size DMA Memory data size - * @brief DMA memory data size - * @{ - */ -#define DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment: Byte */ -#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_MSIZE_0) /*!< Memory data alignment: HalfWord */ -#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_SxCR_MSIZE_1) /*!< Memory data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_mode DMA mode - * @brief DMA mode - * @{ - */ -#define DMA_NORMAL 0x00000000U /*!< Normal mode */ -#define DMA_CIRCULAR ((uint32_t)DMA_SxCR_CIRC) /*!< Circular mode */ -#define DMA_PFCTRL ((uint32_t)DMA_SxCR_PFCTRL) /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_Priority_level DMA Priority level - * @brief DMA priority levels - * @{ - */ -#define DMA_PRIORITY_LOW 0x00000000U /*!< Priority level: Low */ -#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_SxCR_PL_0) /*!< Priority level: Medium */ -#define DMA_PRIORITY_HIGH ((uint32_t)DMA_SxCR_PL_1) /*!< Priority level: High */ -#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_SxCR_PL) /*!< Priority level: Very High */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_direct_mode DMA FIFO direct mode - * @brief DMA FIFO direct mode - * @{ - */ -#define DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable */ -#define DMA_FIFOMODE_ENABLE ((uint32_t)DMA_SxFCR_DMDIS) /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_threshold_level DMA FIFO threshold level - * @brief DMA FIFO level - * @{ - */ -#define DMA_FIFO_THRESHOLD_1QUARTERFULL 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define DMA_FIFO_THRESHOLD_HALFFULL ((uint32_t)DMA_SxFCR_FTH_0) /*!< FIFO threshold half full configuration */ -#define DMA_FIFO_THRESHOLD_3QUARTERSFULL ((uint32_t)DMA_SxFCR_FTH_1) /*!< FIFO threshold 3 quarts full configuration */ -#define DMA_FIFO_THRESHOLD_FULL ((uint32_t)DMA_SxFCR_FTH) /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_Memory_burst DMA Memory burst - * @brief DMA memory burst - * @{ - */ -#define DMA_MBURST_SINGLE 0x00000000U -#define DMA_MBURST_INC4 ((uint32_t)DMA_SxCR_MBURST_0) -#define DMA_MBURST_INC8 ((uint32_t)DMA_SxCR_MBURST_1) -#define DMA_MBURST_INC16 ((uint32_t)DMA_SxCR_MBURST) -/** - * @} - */ - -/** @defgroup DMA_Peripheral_burst DMA Peripheral burst - * @brief DMA peripheral burst - * @{ - */ -#define DMA_PBURST_SINGLE 0x00000000U -#define DMA_PBURST_INC4 ((uint32_t)DMA_SxCR_PBURST_0) -#define DMA_PBURST_INC8 ((uint32_t)DMA_SxCR_PBURST_1) -#define DMA_PBURST_INC16 ((uint32_t)DMA_SxCR_PBURST) -/** - * @} - */ - -/** @defgroup DMA_interrupt_enable_definitions DMA interrupt enable definitions - * @brief DMA interrupts definition - * @{ - */ -#define DMA_IT_TC ((uint32_t)DMA_SxCR_TCIE) -#define DMA_IT_HT ((uint32_t)DMA_SxCR_HTIE) -#define DMA_IT_TE ((uint32_t)DMA_SxCR_TEIE) -#define DMA_IT_DME ((uint32_t)DMA_SxCR_DMEIE) -#define DMA_IT_FE 0x00000080U -/** - * @} - */ - -/** @defgroup DMA_flag_definitions DMA flag definitions - * @brief DMA flag definitions - * @{ - */ -#define DMA_FLAG_FEIF0_4 0x00000001U -#define DMA_FLAG_DMEIF0_4 0x00000004U -#define DMA_FLAG_TEIF0_4 0x00000008U -#define DMA_FLAG_HTIF0_4 0x00000010U -#define DMA_FLAG_TCIF0_4 0x00000020U -#define DMA_FLAG_FEIF1_5 0x00000040U -#define DMA_FLAG_DMEIF1_5 0x00000100U -#define DMA_FLAG_TEIF1_5 0x00000200U -#define DMA_FLAG_HTIF1_5 0x00000400U -#define DMA_FLAG_TCIF1_5 0x00000800U -#define DMA_FLAG_FEIF2_6 0x00010000U -#define DMA_FLAG_DMEIF2_6 0x00040000U -#define DMA_FLAG_TEIF2_6 0x00080000U -#define DMA_FLAG_HTIF2_6 0x00100000U -#define DMA_FLAG_TCIF2_6 0x00200000U -#define DMA_FLAG_FEIF3_7 0x00400000U -#define DMA_FLAG_DMEIF3_7 0x01000000U -#define DMA_FLAG_TEIF3_7 0x02000000U -#define DMA_FLAG_HTIF3_7 0x04000000U -#define DMA_FLAG_TCIF3_7 0x08000000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/** @brief Reset DMA handle state - * @param __HANDLE__ specifies the DMA handle. - * @retval None - */ -#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET) - -/** - * @brief Return the current DMA Stream FIFO filled level. - * @param __HANDLE__ DMA handle - * @retval The FIFO filling state. - * - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full - * and not empty. - * - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full. - * - DMA_FIFOStatus_HalfFull: if more than 1 half-full. - * - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full. - * - DMA_FIFOStatus_Empty: when FIFO is empty - * - DMA_FIFOStatus_Full: when FIFO is full - */ -#define __HAL_DMA_GET_FS(__HANDLE__) (((__HANDLE__)->Instance->FCR & (DMA_SxFCR_FS))) - -/** - * @brief Enable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA_SxCR_EN) - -/** - * @brief Disable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~DMA_SxCR_EN) - -/* Interrupt & Flag management */ - -/** - * @brief Return the current DMA Stream transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer complete flag index. - */ -#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TCIF2_6 :\ - DMA_FLAG_TCIF3_7) - -/** - * @brief Return the current DMA Stream half transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified half transfer complete flag index. - */ -#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_HTIF2_6 :\ - DMA_FLAG_HTIF3_7) - -/** - * @brief Return the current DMA Stream transfer error flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer error flag index. - */ -#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TEIF2_6 :\ - DMA_FLAG_TEIF3_7) - -/** - * @brief Return the current DMA Stream FIFO error flag. - * @param __HANDLE__ DMA handle - * @retval The specified FIFO error flag index. - */ -#define __HAL_DMA_GET_FE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_FEIF2_6 :\ - DMA_FLAG_FEIF3_7) - -/** - * @brief Return the current DMA Stream direct mode error flag. - * @param __HANDLE__ DMA handle - * @retval The specified direct mode error flag index. - */ -#define __HAL_DMA_GET_DME_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_DMEIF2_6 :\ - DMA_FLAG_DMEIF3_7) - -/** - * @brief Get the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__)\ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HISR & (__FLAG__)) : (DMA1->LISR & (__FLAG__))) - -/** - * @brief Clear the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval None - */ -#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) \ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HIFCR = (__FLAG__)) : (DMA1->LIFCR = (__FLAG__))) - -/** - * @brief Enable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR |= (__INTERRUPT__))) - -/** - * @brief Disable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR &= ~(__INTERRUPT__))) - -/** - * @brief Check whether the specified DMA Stream interrupt is enabled or disabled. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval The state of DMA_IT. - */ -#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ - ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) : \ - ((__HANDLE__)->Instance->FCR & (__INTERRUPT__))) - -/** - * @brief Writes the number of data units to be transferred on the DMA Stream. - * @param __HANDLE__ DMA handle - * @param __COUNTER__ Number of data units to be transferred (from 0 to 65535) - * Number of data items depends only on the Peripheral data format. - * - * @note If Peripheral data format is Bytes: number of data units is equal - * to total number of bytes to be transferred. - * - * @note If Peripheral data format is Half-Word: number of data units is - * equal to total number of bytes to be transferred / 2. - * - * @note If Peripheral data format is Word: number of data units is equal - * to total number of bytes to be transferred / 4. - * - * @retval The number of remaining data units in the current DMAy Streamx transfer. - */ -#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->NDTR = (uint16_t)(__COUNTER__)) - -/** - * @brief Returns the number of remaining data units in the current DMAy Streamx transfer. - * @param __HANDLE__ DMA handle - * - * @retval The number of remaining data units in the current DMA Stream transfer. - */ -#define __HAL_DMA_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->NDTR) - - -/* Include DMA HAL Extension module */ -#include "stm32f4xx_hal_dma_ex.h" - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Functions DMA Exported Functions - * @brief DMA Exported functions - * @{ - */ - -/** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group2 I/O operation functions - * @brief I/O operation functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout); -void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_CleanCallbacks(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)); -HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID); - -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group3 Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma); -uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/** - * @} - */ -/* Private Constants -------------------------------------------------------------*/ -/** @defgroup DMA_Private_Constants DMA Private Constants - * @brief DMA private defines and constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DMA_Private_Macros DMA Private Macros - * @brief DMA private macros - * @{ - */ -#if defined (DMA_SxCR_CHSEL_3) -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7) || \ - ((CHANNEL) == DMA_CHANNEL_8) || \ - ((CHANNEL) == DMA_CHANNEL_9) || \ - ((CHANNEL) == DMA_CHANNEL_10)|| \ - ((CHANNEL) == DMA_CHANNEL_11)|| \ - ((CHANNEL) == DMA_CHANNEL_12)|| \ - ((CHANNEL) == DMA_CHANNEL_13)|| \ - ((CHANNEL) == DMA_CHANNEL_14)|| \ - ((CHANNEL) == DMA_CHANNEL_15)) -#else -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7)) -#endif /* DMA_SxCR_CHSEL_3 */ - -#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \ - ((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \ - ((DIRECTION) == DMA_MEMORY_TO_MEMORY)) - -#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x01U) && ((SIZE) < 0x10000U)) - -#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \ - ((STATE) == DMA_PINC_DISABLE)) - -#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \ - ((STATE) == DMA_MINC_DISABLE)) - -#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \ - ((SIZE) == DMA_PDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_PDATAALIGN_WORD)) - -#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \ - ((SIZE) == DMA_MDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_MDATAALIGN_WORD )) - -#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \ - ((MODE) == DMA_CIRCULAR) || \ - ((MODE) == DMA_PFCTRL)) - -#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \ - ((PRIORITY) == DMA_PRIORITY_MEDIUM) || \ - ((PRIORITY) == DMA_PRIORITY_HIGH) || \ - ((PRIORITY) == DMA_PRIORITY_VERY_HIGH)) - -#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMODE_DISABLE ) || \ - ((STATE) == DMA_FIFOMODE_ENABLE)) - -#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFO_THRESHOLD_1QUARTERFULL ) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_HALFFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_3QUARTERSFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_FULL)) - -#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MBURST_SINGLE) || \ - ((BURST) == DMA_MBURST_INC4) || \ - ((BURST) == DMA_MBURST_INC8) || \ - ((BURST) == DMA_MBURST_INC16)) - -#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PBURST_SINGLE) || \ - ((BURST) == DMA_PBURST_INC4) || \ - ((BURST) == DMA_PBURST_INC8) || \ - ((BURST) == DMA_PBURST_INC16)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMA_Private_Functions DMA Private Functions - * @brief DMA private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DMA_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma.h + * @author MCD Application Team + * @brief Header file of DMA HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_DMA_H +#define __STM32F4xx_HAL_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** @defgroup DMA_Exported_Types DMA Exported Types + * @brief DMA Exported Types + * @{ + */ + +/** + * @brief DMA Configuration Structure definition + */ +typedef struct +{ + uint32_t Channel; /*!< Specifies the channel used for the specified stream. + This parameter can be a value of @ref DMA_Channel_selection */ + + uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, + from memory to memory or from peripheral to memory. + This parameter can be a value of @ref DMA_Data_transfer_direction */ + + uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not. + This parameter can be a value of @ref DMA_Peripheral_incremented_mode */ + + uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not. + This parameter can be a value of @ref DMA_Memory_incremented_mode */ + + uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_Peripheral_data_size */ + + uint32_t MemDataAlignment; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_Memory_data_size */ + + uint32_t Mode; /*!< Specifies the operation mode of the DMAy Streamx. + This parameter can be a value of @ref DMA_mode + @note The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Stream */ + + uint32_t Priority; /*!< Specifies the software priority for the DMAy Streamx. + This parameter can be a value of @ref DMA_Priority_level */ + + uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. + This parameter can be a value of @ref DMA_FIFO_direct_mode + @note The Direct mode (FIFO mode disabled) cannot be used if the + memory-to-memory data transfer is configured on the selected stream */ + + uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. + This parameter can be a value of @ref DMA_FIFO_threshold_level */ + + uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. + It specifies the amount of data to be transferred in a single non interruptible + transaction. + This parameter can be a value of @ref DMA_Memory_burst + @note The burst mode is possible only if the address Increment mode is enabled. */ + + uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. + It specifies the amount of data to be transferred in a single non interruptible + transaction. + This parameter can be a value of @ref DMA_Peripheral_burst + @note The burst mode is possible only if the address Increment mode is enabled. */ +}DMA_InitTypeDef; + + +/** + * @brief HAL DMA State structures definition + */ +typedef enum +{ + HAL_DMA_STATE_RESET = 0x00U, /*!< DMA not yet initialized or disabled */ + HAL_DMA_STATE_READY = 0x01U, /*!< DMA initialized and ready for use */ + HAL_DMA_STATE_BUSY = 0x02U, /*!< DMA process is ongoing */ + HAL_DMA_STATE_TIMEOUT = 0x03U, /*!< DMA timeout state */ + HAL_DMA_STATE_ERROR = 0x04U, /*!< DMA error state */ + HAL_DMA_STATE_ABORT = 0x05U, /*!< DMA Abort state */ +}HAL_DMA_StateTypeDef; + +/** + * @brief HAL DMA Error Code structure definition + */ +typedef enum +{ + HAL_DMA_FULL_TRANSFER = 0x00U, /*!< Full transfer */ + HAL_DMA_HALF_TRANSFER = 0x01U /*!< Half Transfer */ +}HAL_DMA_LevelCompleteTypeDef; + +/** + * @brief HAL DMA Error Code structure definition + */ +typedef enum +{ + HAL_DMA_XFER_CPLT_CB_ID = 0x00U, /*!< Full transfer */ + HAL_DMA_XFER_HALFCPLT_CB_ID = 0x01U, /*!< Half Transfer */ + HAL_DMA_XFER_M1CPLT_CB_ID = 0x02U, /*!< M1 Full Transfer */ + HAL_DMA_XFER_M1HALFCPLT_CB_ID = 0x03U, /*!< M1 Half Transfer */ + HAL_DMA_XFER_ERROR_CB_ID = 0x04U, /*!< Error */ + HAL_DMA_XFER_ABORT_CB_ID = 0x05U, /*!< Abort */ + HAL_DMA_XFER_ALL_CB_ID = 0x06U /*!< All */ +}HAL_DMA_CallbackIDTypeDef; + +/** + * @brief DMA handle Structure definition + */ +typedef struct __DMA_HandleTypeDef +{ + DMA_Stream_TypeDef *Instance; /*!< Register base address */ + + DMA_InitTypeDef Init; /*!< DMA communication parameters */ + + HAL_LockTypeDef Lock; /*!< DMA locking object */ + + __IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */ + + void *Parent; /*!< Parent object state */ + + void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */ + + void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */ + + void (* XferM1CpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete Memory1 callback */ + + void (* XferM1HalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Half complete Memory1 callback */ + + void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */ + + void (* XferAbortCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Abort callback */ + + __IO uint32_t ErrorCode; /*!< DMA Error code */ + + uint32_t StreamBaseAddress; /*!< DMA Stream Base Address */ + + uint32_t StreamIndex; /*!< DMA Stream Index */ + +}DMA_HandleTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DMA_Exported_Constants DMA Exported Constants + * @brief DMA Exported constants + * @{ + */ + +/** @defgroup DMA_Error_Code DMA Error Code + * @brief DMA Error Code + * @{ + */ +#define HAL_DMA_ERROR_NONE 0x00000000U /*!< No error */ +#define HAL_DMA_ERROR_TE 0x00000001U /*!< Transfer error */ +#define HAL_DMA_ERROR_FE 0x00000002U /*!< FIFO error */ +#define HAL_DMA_ERROR_DME 0x00000004U /*!< Direct Mode error */ +#define HAL_DMA_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ +#define HAL_DMA_ERROR_PARAM 0x00000040U /*!< Parameter error */ +#define HAL_DMA_ERROR_NO_XFER 0x00000080U /*!< Abort requested with no Xfer ongoing */ +#define HAL_DMA_ERROR_NOT_SUPPORTED 0x00000100U /*!< Not supported mode */ +/** + * @} + */ + +/** @defgroup DMA_Channel_selection DMA Channel selection + * @brief DMA channel selection + * @{ + */ +#define DMA_CHANNEL_0 0x00000000U /*!< DMA Channel 0 */ +#define DMA_CHANNEL_1 0x02000000U /*!< DMA Channel 1 */ +#define DMA_CHANNEL_2 0x04000000U /*!< DMA Channel 2 */ +#define DMA_CHANNEL_3 0x06000000U /*!< DMA Channel 3 */ +#define DMA_CHANNEL_4 0x08000000U /*!< DMA Channel 4 */ +#define DMA_CHANNEL_5 0x0A000000U /*!< DMA Channel 5 */ +#define DMA_CHANNEL_6 0x0C000000U /*!< DMA Channel 6 */ +#define DMA_CHANNEL_7 0x0E000000U /*!< DMA Channel 7 */ +#if defined (DMA_SxCR_CHSEL_3) +#define DMA_CHANNEL_8 0x10000000U /*!< DMA Channel 8 */ +#define DMA_CHANNEL_9 0x12000000U /*!< DMA Channel 9 */ +#define DMA_CHANNEL_10 0x14000000U /*!< DMA Channel 10 */ +#define DMA_CHANNEL_11 0x16000000U /*!< DMA Channel 11 */ +#define DMA_CHANNEL_12 0x18000000U /*!< DMA Channel 12 */ +#define DMA_CHANNEL_13 0x1A000000U /*!< DMA Channel 13 */ +#define DMA_CHANNEL_14 0x1C000000U /*!< DMA Channel 14 */ +#define DMA_CHANNEL_15 0x1E000000U /*!< DMA Channel 15 */ +#endif /* DMA_SxCR_CHSEL_3 */ +/** + * @} + */ + +/** @defgroup DMA_Data_transfer_direction DMA Data transfer direction + * @brief DMA data transfer direction + * @{ + */ +#define DMA_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ +#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_SxCR_DIR_0) /*!< Memory to peripheral direction */ +#define DMA_MEMORY_TO_MEMORY ((uint32_t)DMA_SxCR_DIR_1) /*!< Memory to memory direction */ +/** + * @} + */ + +/** @defgroup DMA_Peripheral_incremented_mode DMA Peripheral incremented mode + * @brief DMA peripheral incremented mode + * @{ + */ +#define DMA_PINC_ENABLE ((uint32_t)DMA_SxCR_PINC) /*!< Peripheral increment mode enable */ +#define DMA_PINC_DISABLE 0x00000000U /*!< Peripheral increment mode disable */ +/** + * @} + */ + +/** @defgroup DMA_Memory_incremented_mode DMA Memory incremented mode + * @brief DMA memory incremented mode + * @{ + */ +#define DMA_MINC_ENABLE ((uint32_t)DMA_SxCR_MINC) /*!< Memory increment mode enable */ +#define DMA_MINC_DISABLE 0x00000000U /*!< Memory increment mode disable */ +/** + * @} + */ + +/** @defgroup DMA_Peripheral_data_size DMA Peripheral data size + * @brief DMA peripheral data size + * @{ + */ +#define DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment: Byte */ +#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_PSIZE_0) /*!< Peripheral data alignment: HalfWord */ +#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_SxCR_PSIZE_1) /*!< Peripheral data alignment: Word */ +/** + * @} + */ + +/** @defgroup DMA_Memory_data_size DMA Memory data size + * @brief DMA memory data size + * @{ + */ +#define DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment: Byte */ +#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_MSIZE_0) /*!< Memory data alignment: HalfWord */ +#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_SxCR_MSIZE_1) /*!< Memory data alignment: Word */ +/** + * @} + */ + +/** @defgroup DMA_mode DMA mode + * @brief DMA mode + * @{ + */ +#define DMA_NORMAL 0x00000000U /*!< Normal mode */ +#define DMA_CIRCULAR ((uint32_t)DMA_SxCR_CIRC) /*!< Circular mode */ +#define DMA_PFCTRL ((uint32_t)DMA_SxCR_PFCTRL) /*!< Peripheral flow control mode */ +/** + * @} + */ + +/** @defgroup DMA_Priority_level DMA Priority level + * @brief DMA priority levels + * @{ + */ +#define DMA_PRIORITY_LOW 0x00000000U /*!< Priority level: Low */ +#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_SxCR_PL_0) /*!< Priority level: Medium */ +#define DMA_PRIORITY_HIGH ((uint32_t)DMA_SxCR_PL_1) /*!< Priority level: High */ +#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_SxCR_PL) /*!< Priority level: Very High */ +/** + * @} + */ + +/** @defgroup DMA_FIFO_direct_mode DMA FIFO direct mode + * @brief DMA FIFO direct mode + * @{ + */ +#define DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable */ +#define DMA_FIFOMODE_ENABLE ((uint32_t)DMA_SxFCR_DMDIS) /*!< FIFO mode enable */ +/** + * @} + */ + +/** @defgroup DMA_FIFO_threshold_level DMA FIFO threshold level + * @brief DMA FIFO level + * @{ + */ +#define DMA_FIFO_THRESHOLD_1QUARTERFULL 0x00000000U /*!< FIFO threshold 1 quart full configuration */ +#define DMA_FIFO_THRESHOLD_HALFFULL ((uint32_t)DMA_SxFCR_FTH_0) /*!< FIFO threshold half full configuration */ +#define DMA_FIFO_THRESHOLD_3QUARTERSFULL ((uint32_t)DMA_SxFCR_FTH_1) /*!< FIFO threshold 3 quarts full configuration */ +#define DMA_FIFO_THRESHOLD_FULL ((uint32_t)DMA_SxFCR_FTH) /*!< FIFO threshold full configuration */ +/** + * @} + */ + +/** @defgroup DMA_Memory_burst DMA Memory burst + * @brief DMA memory burst + * @{ + */ +#define DMA_MBURST_SINGLE 0x00000000U +#define DMA_MBURST_INC4 ((uint32_t)DMA_SxCR_MBURST_0) +#define DMA_MBURST_INC8 ((uint32_t)DMA_SxCR_MBURST_1) +#define DMA_MBURST_INC16 ((uint32_t)DMA_SxCR_MBURST) +/** + * @} + */ + +/** @defgroup DMA_Peripheral_burst DMA Peripheral burst + * @brief DMA peripheral burst + * @{ + */ +#define DMA_PBURST_SINGLE 0x00000000U +#define DMA_PBURST_INC4 ((uint32_t)DMA_SxCR_PBURST_0) +#define DMA_PBURST_INC8 ((uint32_t)DMA_SxCR_PBURST_1) +#define DMA_PBURST_INC16 ((uint32_t)DMA_SxCR_PBURST) +/** + * @} + */ + +/** @defgroup DMA_interrupt_enable_definitions DMA interrupt enable definitions + * @brief DMA interrupts definition + * @{ + */ +#define DMA_IT_TC ((uint32_t)DMA_SxCR_TCIE) +#define DMA_IT_HT ((uint32_t)DMA_SxCR_HTIE) +#define DMA_IT_TE ((uint32_t)DMA_SxCR_TEIE) +#define DMA_IT_DME ((uint32_t)DMA_SxCR_DMEIE) +#define DMA_IT_FE 0x00000080U +/** + * @} + */ + +/** @defgroup DMA_flag_definitions DMA flag definitions + * @brief DMA flag definitions + * @{ + */ +#define DMA_FLAG_FEIF0_4 0x00000001U +#define DMA_FLAG_DMEIF0_4 0x00000004U +#define DMA_FLAG_TEIF0_4 0x00000008U +#define DMA_FLAG_HTIF0_4 0x00000010U +#define DMA_FLAG_TCIF0_4 0x00000020U +#define DMA_FLAG_FEIF1_5 0x00000040U +#define DMA_FLAG_DMEIF1_5 0x00000100U +#define DMA_FLAG_TEIF1_5 0x00000200U +#define DMA_FLAG_HTIF1_5 0x00000400U +#define DMA_FLAG_TCIF1_5 0x00000800U +#define DMA_FLAG_FEIF2_6 0x00010000U +#define DMA_FLAG_DMEIF2_6 0x00040000U +#define DMA_FLAG_TEIF2_6 0x00080000U +#define DMA_FLAG_HTIF2_6 0x00100000U +#define DMA_FLAG_TCIF2_6 0x00200000U +#define DMA_FLAG_FEIF3_7 0x00400000U +#define DMA_FLAG_DMEIF3_7 0x01000000U +#define DMA_FLAG_TEIF3_7 0x02000000U +#define DMA_FLAG_HTIF3_7 0x04000000U +#define DMA_FLAG_TCIF3_7 0x08000000U +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ + +/** @brief Reset DMA handle state + * @param __HANDLE__ specifies the DMA handle. + * @retval None + */ +#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET) + +/** + * @brief Return the current DMA Stream FIFO filled level. + * @param __HANDLE__ DMA handle + * @retval The FIFO filling state. + * - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full + * and not empty. + * - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full. + * - DMA_FIFOStatus_HalfFull: if more than 1 half-full. + * - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full. + * - DMA_FIFOStatus_Empty: when FIFO is empty + * - DMA_FIFOStatus_Full: when FIFO is full + */ +#define __HAL_DMA_GET_FS(__HANDLE__) (((__HANDLE__)->Instance->FCR & (DMA_SxFCR_FS))) + +/** + * @brief Enable the specified DMA Stream. + * @param __HANDLE__ DMA handle + * @retval None + */ +#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA_SxCR_EN) + +/** + * @brief Disable the specified DMA Stream. + * @param __HANDLE__ DMA handle + * @retval None + */ +#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~DMA_SxCR_EN) + +/* Interrupt & Flag management */ + +/** + * @brief Return the current DMA Stream transfer complete flag. + * @param __HANDLE__ DMA handle + * @retval The specified transfer complete flag index. + */ +#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \ +(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TCIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TCIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TCIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TCIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TCIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TCIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TCIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TCIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TCIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TCIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TCIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TCIF2_6 :\ + DMA_FLAG_TCIF3_7) + +/** + * @brief Return the current DMA Stream half transfer complete flag. + * @param __HANDLE__ DMA handle + * @retval The specified half transfer complete flag index. + */ +#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\ +(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_HTIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_HTIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_HTIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_HTIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_HTIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_HTIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_HTIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_HTIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_HTIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_HTIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_HTIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_HTIF2_6 :\ + DMA_FLAG_HTIF3_7) + +/** + * @brief Return the current DMA Stream transfer error flag. + * @param __HANDLE__ DMA handle + * @retval The specified transfer error flag index. + */ +#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\ +(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TEIF2_6 :\ + DMA_FLAG_TEIF3_7) + +/** + * @brief Return the current DMA Stream FIFO error flag. + * @param __HANDLE__ DMA handle + * @retval The specified FIFO error flag index. + */ +#define __HAL_DMA_GET_FE_FLAG_INDEX(__HANDLE__)\ +(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_FEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_FEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_FEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_FEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_FEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_FEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_FEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_FEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_FEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_FEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_FEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_FEIF2_6 :\ + DMA_FLAG_FEIF3_7) + +/** + * @brief Return the current DMA Stream direct mode error flag. + * @param __HANDLE__ DMA handle + * @retval The specified direct mode error flag index. + */ +#define __HAL_DMA_GET_DME_FLAG_INDEX(__HANDLE__)\ +(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_DMEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_DMEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_DMEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_DMEIF0_4 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_DMEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_DMEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_DMEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_DMEIF1_5 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_DMEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_DMEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_DMEIF2_6 :\ + ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_DMEIF2_6 :\ + DMA_FLAG_DMEIF3_7) + +/** + * @brief Get the DMA Stream pending flags. + * @param __HANDLE__ DMA handle + * @param __FLAG__ Get the specified flag. + * This parameter can be any combination of the following values: + * @arg DMA_FLAG_TCIFx: Transfer complete flag. + * @arg DMA_FLAG_HTIFx: Half transfer complete flag. + * @arg DMA_FLAG_TEIFx: Transfer error flag. + * @arg DMA_FLAG_DMEIFx: Direct mode error flag. + * @arg DMA_FLAG_FEIFx: FIFO error flag. + * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. + * @retval The state of FLAG (SET or RESET). + */ +#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__)\ +(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HISR & (__FLAG__)) :\ + ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LISR & (__FLAG__)) :\ + ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HISR & (__FLAG__)) : (DMA1->LISR & (__FLAG__))) + +/** + * @brief Clear the DMA Stream pending flags. + * @param __HANDLE__ DMA handle + * @param __FLAG__ specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg DMA_FLAG_TCIFx: Transfer complete flag. + * @arg DMA_FLAG_HTIFx: Half transfer complete flag. + * @arg DMA_FLAG_TEIFx: Transfer error flag. + * @arg DMA_FLAG_DMEIFx: Direct mode error flag. + * @arg DMA_FLAG_FEIFx: FIFO error flag. + * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. + * @retval None + */ +#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) \ +(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HIFCR = (__FLAG__)) :\ + ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LIFCR = (__FLAG__)) :\ + ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HIFCR = (__FLAG__)) : (DMA1->LIFCR = (__FLAG__))) + +/** + * @brief Enable the specified DMA Stream interrupts. + * @param __HANDLE__ DMA handle + * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask. + * @arg DMA_IT_HT: Half transfer complete interrupt mask. + * @arg DMA_IT_TE: Transfer error interrupt mask. + * @arg DMA_IT_FE: FIFO error interrupt mask. + * @arg DMA_IT_DME: Direct mode error interrupt. + * @retval None + */ +#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ +((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR |= (__INTERRUPT__))) + +/** + * @brief Disable the specified DMA Stream interrupts. + * @param __HANDLE__ DMA handle + * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask. + * @arg DMA_IT_HT: Half transfer complete interrupt mask. + * @arg DMA_IT_TE: Transfer error interrupt mask. + * @arg DMA_IT_FE: FIFO error interrupt mask. + * @arg DMA_IT_DME: Direct mode error interrupt. + * @retval None + */ +#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ +((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR &= ~(__INTERRUPT__))) + +/** + * @brief Check whether the specified DMA Stream interrupt is enabled or disabled. + * @param __HANDLE__ DMA handle + * @param __INTERRUPT__ specifies the DMA interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask. + * @arg DMA_IT_HT: Half transfer complete interrupt mask. + * @arg DMA_IT_TE: Transfer error interrupt mask. + * @arg DMA_IT_FE: FIFO error interrupt mask. + * @arg DMA_IT_DME: Direct mode error interrupt. + * @retval The state of DMA_IT. + */ +#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ + ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) : \ + ((__HANDLE__)->Instance->FCR & (__INTERRUPT__))) + +/** + * @brief Writes the number of data units to be transferred on the DMA Stream. + * @param __HANDLE__ DMA handle + * @param __COUNTER__ Number of data units to be transferred (from 0 to 65535) + * Number of data items depends only on the Peripheral data format. + * + * @note If Peripheral data format is Bytes: number of data units is equal + * to total number of bytes to be transferred. + * + * @note If Peripheral data format is Half-Word: number of data units is + * equal to total number of bytes to be transferred / 2. + * + * @note If Peripheral data format is Word: number of data units is equal + * to total number of bytes to be transferred / 4. + * + * @retval The number of remaining data units in the current DMAy Streamx transfer. + */ +#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->NDTR = (uint16_t)(__COUNTER__)) + +/** + * @brief Returns the number of remaining data units in the current DMAy Streamx transfer. + * @param __HANDLE__ DMA handle + * + * @retval The number of remaining data units in the current DMA Stream transfer. + */ +#define __HAL_DMA_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->NDTR) + + +/* Include DMA HAL Extension module */ +#include "stm32f4xx_hal_dma_ex.h" + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup DMA_Exported_Functions DMA Exported Functions + * @brief DMA Exported functions + * @{ + */ + +/** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and de-initialization functions + * @{ + */ +HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma); +HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma); +/** + * @} + */ + +/** @defgroup DMA_Exported_Functions_Group2 I/O operation functions + * @brief I/O operation functions + * @{ + */ +HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma); +HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma); +HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout); +void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma); +HAL_StatusTypeDef HAL_DMA_CleanCallbacks(DMA_HandleTypeDef *hdma); +HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)); +HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID); + +/** + * @} + */ + +/** @defgroup DMA_Exported_Functions_Group3 Peripheral State functions + * @brief Peripheral State functions + * @{ + */ +HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma); +uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma); +/** + * @} + */ +/** + * @} + */ +/* Private Constants -------------------------------------------------------------*/ +/** @defgroup DMA_Private_Constants DMA Private Constants + * @brief DMA private defines and constants + * @{ + */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup DMA_Private_Macros DMA Private Macros + * @brief DMA private macros + * @{ + */ +#if defined (DMA_SxCR_CHSEL_3) +#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ + ((CHANNEL) == DMA_CHANNEL_1) || \ + ((CHANNEL) == DMA_CHANNEL_2) || \ + ((CHANNEL) == DMA_CHANNEL_3) || \ + ((CHANNEL) == DMA_CHANNEL_4) || \ + ((CHANNEL) == DMA_CHANNEL_5) || \ + ((CHANNEL) == DMA_CHANNEL_6) || \ + ((CHANNEL) == DMA_CHANNEL_7) || \ + ((CHANNEL) == DMA_CHANNEL_8) || \ + ((CHANNEL) == DMA_CHANNEL_9) || \ + ((CHANNEL) == DMA_CHANNEL_10)|| \ + ((CHANNEL) == DMA_CHANNEL_11)|| \ + ((CHANNEL) == DMA_CHANNEL_12)|| \ + ((CHANNEL) == DMA_CHANNEL_13)|| \ + ((CHANNEL) == DMA_CHANNEL_14)|| \ + ((CHANNEL) == DMA_CHANNEL_15)) +#else +#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ + ((CHANNEL) == DMA_CHANNEL_1) || \ + ((CHANNEL) == DMA_CHANNEL_2) || \ + ((CHANNEL) == DMA_CHANNEL_3) || \ + ((CHANNEL) == DMA_CHANNEL_4) || \ + ((CHANNEL) == DMA_CHANNEL_5) || \ + ((CHANNEL) == DMA_CHANNEL_6) || \ + ((CHANNEL) == DMA_CHANNEL_7)) +#endif /* DMA_SxCR_CHSEL_3 */ + +#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \ + ((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \ + ((DIRECTION) == DMA_MEMORY_TO_MEMORY)) + +#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x01U) && ((SIZE) < 0x10000U)) + +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \ + ((STATE) == DMA_PINC_DISABLE)) + +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \ + ((STATE) == DMA_MINC_DISABLE)) + +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \ + ((SIZE) == DMA_PDATAALIGN_HALFWORD) || \ + ((SIZE) == DMA_PDATAALIGN_WORD)) + +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \ + ((SIZE) == DMA_MDATAALIGN_HALFWORD) || \ + ((SIZE) == DMA_MDATAALIGN_WORD )) + +#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \ + ((MODE) == DMA_CIRCULAR) || \ + ((MODE) == DMA_PFCTRL)) + +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \ + ((PRIORITY) == DMA_PRIORITY_MEDIUM) || \ + ((PRIORITY) == DMA_PRIORITY_HIGH) || \ + ((PRIORITY) == DMA_PRIORITY_VERY_HIGH)) + +#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMODE_DISABLE ) || \ + ((STATE) == DMA_FIFOMODE_ENABLE)) + +#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFO_THRESHOLD_1QUARTERFULL ) || \ + ((THRESHOLD) == DMA_FIFO_THRESHOLD_HALFFULL) || \ + ((THRESHOLD) == DMA_FIFO_THRESHOLD_3QUARTERSFULL) || \ + ((THRESHOLD) == DMA_FIFO_THRESHOLD_FULL)) + +#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MBURST_SINGLE) || \ + ((BURST) == DMA_MBURST_INC4) || \ + ((BURST) == DMA_MBURST_INC8) || \ + ((BURST) == DMA_MBURST_INC16)) + +#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PBURST_SINGLE) || \ + ((BURST) == DMA_PBURST_INC4) || \ + ((BURST) == DMA_PBURST_INC8) || \ + ((BURST) == DMA_PBURST_INC16)) +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup DMA_Private_Functions DMA Private Functions + * @brief DMA private functions + * @{ + */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_DMA_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h index 9858c74..266c1fa 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h @@ -1,102 +1,102 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma_ex.h - * @author MCD Application Team - * @brief Header file of DMA HAL extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_EX_H -#define __STM32F4xx_HAL_DMA_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMAEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Types DMAEx Exported Types - * @brief DMAEx Exported types - * @{ - */ - -/** - * @brief HAL DMA Memory definition - */ -typedef enum -{ - MEMORY0 = 0x00U, /*!< Memory 0 */ - MEMORY1 = 0x01U /*!< Memory 1 */ -}HAL_DMA_MemoryTypeDef; - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Functions DMAEx Exported Functions - * @brief DMAEx Exported functions - * @{ - */ - -/** @defgroup DMAEx_Exported_Functions_Group1 Extended features functions - * @brief Extended features functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory); - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMAEx_Private_Functions DMAEx Private Functions - * @brief DMAEx Private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_HAL_DMA_EX_H*/ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma_ex.h + * @author MCD Application Team + * @brief Header file of DMA HAL extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_DMA_EX_H +#define __STM32F4xx_HAL_DMA_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup DMAEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup DMAEx_Exported_Types DMAEx Exported Types + * @brief DMAEx Exported types + * @{ + */ + +/** + * @brief HAL DMA Memory definition + */ +typedef enum +{ + MEMORY0 = 0x00U, /*!< Memory 0 */ + MEMORY1 = 0x01U /*!< Memory 1 */ +}HAL_DMA_MemoryTypeDef; + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup DMAEx_Exported_Functions DMAEx Exported Functions + * @brief DMAEx Exported functions + * @{ + */ + +/** @defgroup DMAEx_Exported_Functions_Group1 Extended features functions + * @brief Extended features functions + * @{ + */ + +/* IO operation functions *******************************************************/ +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); +HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory); + +/** + * @} + */ +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup DMAEx_Private_Functions DMAEx Private Functions + * @brief DMAEx Private functions + * @{ + */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_HAL_DMA_EX_H*/ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h index b18a228..a7af121 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h @@ -1,366 +1,366 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_exti.h - * @author MCD Application Team - * @brief Header file of EXTI HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2018 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS.Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32f4xx_HAL_EXTI_H -#define STM32f4xx_HAL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup EXTI EXTI - * @brief EXTI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup EXTI_Exported_Types EXTI Exported Types - * @{ - */ -typedef enum -{ - HAL_EXTI_COMMON_CB_ID = 0x00U -} EXTI_CallbackIDTypeDef; - -/** - * @brief EXTI Handle structure definition - */ -typedef struct -{ - uint32_t Line; /*!< Exti line number */ - void (* PendingCallback)(void); /*!< Exti pending callback */ -} EXTI_HandleTypeDef; - -/** - * @brief EXTI Configuration structure definition - */ -typedef struct -{ - uint32_t Line; /*!< The Exti line to be configured. This parameter - can be a value of @ref EXTI_Line */ - uint32_t Mode; /*!< The Exit Mode to be configured for a core. - This parameter can be a combination of @ref EXTI_Mode */ - uint32_t Trigger; /*!< The Exti Trigger to be configured. This parameter - can be a value of @ref EXTI_Trigger */ - uint32_t GPIOSel; /*!< The Exti GPIO multiplexer selection to be configured. - This parameter is only possible for line 0 to 15. It - can be a value of @ref EXTI_GPIOSel */ -} EXTI_ConfigTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_Line EXTI Line - * @{ - */ -#define EXTI_LINE_0 (EXTI_GPIO | 0x00u) /*!< External interrupt line 0 */ -#define EXTI_LINE_1 (EXTI_GPIO | 0x01u) /*!< External interrupt line 1 */ -#define EXTI_LINE_2 (EXTI_GPIO | 0x02u) /*!< External interrupt line 2 */ -#define EXTI_LINE_3 (EXTI_GPIO | 0x03u) /*!< External interrupt line 3 */ -#define EXTI_LINE_4 (EXTI_GPIO | 0x04u) /*!< External interrupt line 4 */ -#define EXTI_LINE_5 (EXTI_GPIO | 0x05u) /*!< External interrupt line 5 */ -#define EXTI_LINE_6 (EXTI_GPIO | 0x06u) /*!< External interrupt line 6 */ -#define EXTI_LINE_7 (EXTI_GPIO | 0x07u) /*!< External interrupt line 7 */ -#define EXTI_LINE_8 (EXTI_GPIO | 0x08u) /*!< External interrupt line 8 */ -#define EXTI_LINE_9 (EXTI_GPIO | 0x09u) /*!< External interrupt line 9 */ -#define EXTI_LINE_10 (EXTI_GPIO | 0x0Au) /*!< External interrupt line 10 */ -#define EXTI_LINE_11 (EXTI_GPIO | 0x0Bu) /*!< External interrupt line 11 */ -#define EXTI_LINE_12 (EXTI_GPIO | 0x0Cu) /*!< External interrupt line 12 */ -#define EXTI_LINE_13 (EXTI_GPIO | 0x0Du) /*!< External interrupt line 13 */ -#define EXTI_LINE_14 (EXTI_GPIO | 0x0Eu) /*!< External interrupt line 14 */ -#define EXTI_LINE_15 (EXTI_GPIO | 0x0Fu) /*!< External interrupt line 15 */ -#define EXTI_LINE_16 (EXTI_CONFIG | 0x10u) /*!< External interrupt line 16 Connected to the PVD Output */ -#define EXTI_LINE_17 (EXTI_CONFIG | 0x11u) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -#if defined(EXTI_IMR_IM18) -#define EXTI_LINE_18 (EXTI_CONFIG | 0x12u) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */ -#else -#define EXTI_LINE_18 (EXTI_RESERVED | 0x12u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM18 */ -#if defined(EXTI_IMR_IM19) -#define EXTI_LINE_19 (EXTI_CONFIG | 0x13u) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ -#else -#define EXTI_LINE_19 (EXTI_RESERVED | 0x13u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM19 */ -#if defined(EXTI_IMR_IM20) -#define EXTI_LINE_20 (EXTI_CONFIG | 0x14u) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */ -#else -#define EXTI_LINE_20 (EXTI_RESERVED | 0x14u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM20 */ -#define EXTI_LINE_21 (EXTI_CONFIG | 0x15u) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ -#define EXTI_LINE_22 (EXTI_CONFIG | 0x16u) /*!< External interrupt line 22 Connected to the RTC Wakeup event */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_23 (EXTI_CONFIG | 0x17u) /*!< External interrupt line 23 Connected to the LPTIM1 asynchronous event */ -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/** @defgroup EXTI_Mode EXTI Mode - * @{ - */ -#define EXTI_MODE_NONE 0x00000000u -#define EXTI_MODE_INTERRUPT 0x00000001u -#define EXTI_MODE_EVENT 0x00000002u -/** - * @} - */ - -/** @defgroup EXTI_Trigger EXTI Trigger - * @{ - */ - -#define EXTI_TRIGGER_NONE 0x00000000u -#define EXTI_TRIGGER_RISING 0x00000001u -#define EXTI_TRIGGER_FALLING 0x00000002u -#define EXTI_TRIGGER_RISING_FALLING (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) -/** - * @} - */ - -/** @defgroup EXTI_GPIOSel EXTI GPIOSel - * @brief - * @{ - */ -#define EXTI_GPIOA 0x00000000u -#define EXTI_GPIOB 0x00000001u -#define EXTI_GPIOC 0x00000002u -#if defined (GPIOD) -#define EXTI_GPIOD 0x00000003u -#endif /* GPIOD */ -#if defined (GPIOE) -#define EXTI_GPIOE 0x00000004u -#endif /* GPIOE */ -#if defined (GPIOF) -#define EXTI_GPIOF 0x00000005u -#endif /* GPIOF */ -#if defined (GPIOG) -#define EXTI_GPIOG 0x00000006u -#endif /* GPIOG */ -#if defined (GPIOH) -#define EXTI_GPIOH 0x00000007u -#endif /* GPIOH */ -#if defined (GPIOI) -#define EXTI_GPIOI 0x00000008u -#endif /* GPIOI */ -#if defined (GPIOJ) -#define EXTI_GPIOJ 0x00000009u -#endif /* GPIOJ */ -#if defined (GPIOK) -#define EXTI_GPIOK 0x0000000Au -#endif /* GPIOK */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Private constants --------------------------------------------------------*/ -/** @defgroup EXTI_Private_Constants EXTI Private Constants - * @{ - */ -/** - * @brief EXTI Line property definition - */ -#define EXTI_PROPERTY_SHIFT 24u -#define EXTI_CONFIG (0x02uL << EXTI_PROPERTY_SHIFT) -#define EXTI_GPIO ((0x04uL << EXTI_PROPERTY_SHIFT) | EXTI_CONFIG) -#define EXTI_RESERVED (0x08uL << EXTI_PROPERTY_SHIFT) -#define EXTI_PROPERTY_MASK (EXTI_CONFIG | EXTI_GPIO) - -/** - * @brief EXTI bit usage - */ -#define EXTI_PIN_MASK 0x0000001Fu - -/** - * @brief EXTI Mask for interrupt & event mode - */ -#define EXTI_MODE_MASK (EXTI_MODE_EVENT | EXTI_MODE_INTERRUPT) - -/** - * @brief EXTI Mask for trigger possibilities - */ -#define EXTI_TRIGGER_MASK (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) - -/** - * @brief EXTI Line number - */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_NB 24UL -#else -#define EXTI_LINE_NB 23UL -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup EXTI_Private_Macros EXTI Private Macros - * @{ - */ -#define IS_EXTI_LINE(__EXTI_LINE__) ((((__EXTI_LINE__) & ~(EXTI_PROPERTY_MASK | EXTI_PIN_MASK)) == 0x00u) && \ - ((((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_CONFIG) || \ - (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_GPIO)) && \ - (((__EXTI_LINE__) & EXTI_PIN_MASK) < EXTI_LINE_NB)) - -#define IS_EXTI_MODE(__EXTI_LINE__) ((((__EXTI_LINE__) & EXTI_MODE_MASK) != 0x00u) && \ - (((__EXTI_LINE__) & ~EXTI_MODE_MASK) == 0x00u)) - -#define IS_EXTI_TRIGGER(__EXTI_LINE__) (((__EXTI_LINE__) & ~EXTI_TRIGGER_MASK) == 0x00u) - -#define IS_EXTI_PENDING_EDGE(__EXTI_LINE__) ((__EXTI_LINE__) == EXTI_TRIGGER_RISING_FALLING) - -#define IS_EXTI_CONFIG_LINE(__EXTI_LINE__) (((__EXTI_LINE__) & EXTI_CONFIG) != 0x00u) - -#if !defined (GPIOD) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOE) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOF) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOI) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOJ) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI)) -#else -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI) || \ - ((__PORT__) == EXTI_GPIOJ) || \ - ((__PORT__) == EXTI_GPIOK)) -#endif /* GPIOD */ - -#define IS_EXTI_GPIO_PIN(__PIN__) ((__PIN__) < 16U) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Functions EXTI Exported Functions - * @brief EXTI Exported Functions - * @{ - */ - -/** @defgroup EXTI_Exported_Functions_Group1 Configuration functions - * @brief Configuration functions - * @{ - */ -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti); -HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)); -HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine); -/** - * @} - */ - -/** @defgroup EXTI_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * @{ - */ -/* IO operation functions *****************************************************/ -void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti); -uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32f4xx_HAL_EXTI_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_exti.h + * @author MCD Application Team + * @brief Header file of EXTI HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2018 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS.Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32f4xx_HAL_EXTI_H +#define STM32f4xx_HAL_EXTI_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup EXTI EXTI + * @brief EXTI HAL module driver + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** @defgroup EXTI_Exported_Types EXTI Exported Types + * @{ + */ +typedef enum +{ + HAL_EXTI_COMMON_CB_ID = 0x00U +} EXTI_CallbackIDTypeDef; + +/** + * @brief EXTI Handle structure definition + */ +typedef struct +{ + uint32_t Line; /*!< Exti line number */ + void (* PendingCallback)(void); /*!< Exti pending callback */ +} EXTI_HandleTypeDef; + +/** + * @brief EXTI Configuration structure definition + */ +typedef struct +{ + uint32_t Line; /*!< The Exti line to be configured. This parameter + can be a value of @ref EXTI_Line */ + uint32_t Mode; /*!< The Exit Mode to be configured for a core. + This parameter can be a combination of @ref EXTI_Mode */ + uint32_t Trigger; /*!< The Exti Trigger to be configured. This parameter + can be a value of @ref EXTI_Trigger */ + uint32_t GPIOSel; /*!< The Exti GPIO multiplexer selection to be configured. + This parameter is only possible for line 0 to 15. It + can be a value of @ref EXTI_GPIOSel */ +} EXTI_ConfigTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup EXTI_Exported_Constants EXTI Exported Constants + * @{ + */ + +/** @defgroup EXTI_Line EXTI Line + * @{ + */ +#define EXTI_LINE_0 (EXTI_GPIO | 0x00u) /*!< External interrupt line 0 */ +#define EXTI_LINE_1 (EXTI_GPIO | 0x01u) /*!< External interrupt line 1 */ +#define EXTI_LINE_2 (EXTI_GPIO | 0x02u) /*!< External interrupt line 2 */ +#define EXTI_LINE_3 (EXTI_GPIO | 0x03u) /*!< External interrupt line 3 */ +#define EXTI_LINE_4 (EXTI_GPIO | 0x04u) /*!< External interrupt line 4 */ +#define EXTI_LINE_5 (EXTI_GPIO | 0x05u) /*!< External interrupt line 5 */ +#define EXTI_LINE_6 (EXTI_GPIO | 0x06u) /*!< External interrupt line 6 */ +#define EXTI_LINE_7 (EXTI_GPIO | 0x07u) /*!< External interrupt line 7 */ +#define EXTI_LINE_8 (EXTI_GPIO | 0x08u) /*!< External interrupt line 8 */ +#define EXTI_LINE_9 (EXTI_GPIO | 0x09u) /*!< External interrupt line 9 */ +#define EXTI_LINE_10 (EXTI_GPIO | 0x0Au) /*!< External interrupt line 10 */ +#define EXTI_LINE_11 (EXTI_GPIO | 0x0Bu) /*!< External interrupt line 11 */ +#define EXTI_LINE_12 (EXTI_GPIO | 0x0Cu) /*!< External interrupt line 12 */ +#define EXTI_LINE_13 (EXTI_GPIO | 0x0Du) /*!< External interrupt line 13 */ +#define EXTI_LINE_14 (EXTI_GPIO | 0x0Eu) /*!< External interrupt line 14 */ +#define EXTI_LINE_15 (EXTI_GPIO | 0x0Fu) /*!< External interrupt line 15 */ +#define EXTI_LINE_16 (EXTI_CONFIG | 0x10u) /*!< External interrupt line 16 Connected to the PVD Output */ +#define EXTI_LINE_17 (EXTI_CONFIG | 0x11u) /*!< External interrupt line 17 Connected to the RTC Alarm event */ +#if defined(EXTI_IMR_IM18) +#define EXTI_LINE_18 (EXTI_CONFIG | 0x12u) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */ +#else +#define EXTI_LINE_18 (EXTI_RESERVED | 0x12u) /*!< No interrupt supported in this line */ +#endif /* EXTI_IMR_IM18 */ +#if defined(EXTI_IMR_IM19) +#define EXTI_LINE_19 (EXTI_CONFIG | 0x13u) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ +#else +#define EXTI_LINE_19 (EXTI_RESERVED | 0x13u) /*!< No interrupt supported in this line */ +#endif /* EXTI_IMR_IM19 */ +#if defined(EXTI_IMR_IM20) +#define EXTI_LINE_20 (EXTI_CONFIG | 0x14u) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */ +#else +#define EXTI_LINE_20 (EXTI_RESERVED | 0x14u) /*!< No interrupt supported in this line */ +#endif /* EXTI_IMR_IM20 */ +#define EXTI_LINE_21 (EXTI_CONFIG | 0x15u) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ +#define EXTI_LINE_22 (EXTI_CONFIG | 0x16u) /*!< External interrupt line 22 Connected to the RTC Wakeup event */ +#if defined(EXTI_IMR_IM23) +#define EXTI_LINE_23 (EXTI_CONFIG | 0x17u) /*!< External interrupt line 23 Connected to the LPTIM1 asynchronous event */ +#endif /* EXTI_IMR_IM23 */ + +/** + * @} + */ + +/** @defgroup EXTI_Mode EXTI Mode + * @{ + */ +#define EXTI_MODE_NONE 0x00000000u +#define EXTI_MODE_INTERRUPT 0x00000001u +#define EXTI_MODE_EVENT 0x00000002u +/** + * @} + */ + +/** @defgroup EXTI_Trigger EXTI Trigger + * @{ + */ + +#define EXTI_TRIGGER_NONE 0x00000000u +#define EXTI_TRIGGER_RISING 0x00000001u +#define EXTI_TRIGGER_FALLING 0x00000002u +#define EXTI_TRIGGER_RISING_FALLING (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) +/** + * @} + */ + +/** @defgroup EXTI_GPIOSel EXTI GPIOSel + * @brief + * @{ + */ +#define EXTI_GPIOA 0x00000000u +#define EXTI_GPIOB 0x00000001u +#define EXTI_GPIOC 0x00000002u +#if defined (GPIOD) +#define EXTI_GPIOD 0x00000003u +#endif /* GPIOD */ +#if defined (GPIOE) +#define EXTI_GPIOE 0x00000004u +#endif /* GPIOE */ +#if defined (GPIOF) +#define EXTI_GPIOF 0x00000005u +#endif /* GPIOF */ +#if defined (GPIOG) +#define EXTI_GPIOG 0x00000006u +#endif /* GPIOG */ +#if defined (GPIOH) +#define EXTI_GPIOH 0x00000007u +#endif /* GPIOH */ +#if defined (GPIOI) +#define EXTI_GPIOI 0x00000008u +#endif /* GPIOI */ +#if defined (GPIOJ) +#define EXTI_GPIOJ 0x00000009u +#endif /* GPIOJ */ +#if defined (GPIOK) +#define EXTI_GPIOK 0x0000000Au +#endif /* GPIOK */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup EXTI_Exported_Macros EXTI Exported Macros + * @{ + */ + +/** + * @} + */ + +/* Private constants --------------------------------------------------------*/ +/** @defgroup EXTI_Private_Constants EXTI Private Constants + * @{ + */ +/** + * @brief EXTI Line property definition + */ +#define EXTI_PROPERTY_SHIFT 24u +#define EXTI_CONFIG (0x02uL << EXTI_PROPERTY_SHIFT) +#define EXTI_GPIO ((0x04uL << EXTI_PROPERTY_SHIFT) | EXTI_CONFIG) +#define EXTI_RESERVED (0x08uL << EXTI_PROPERTY_SHIFT) +#define EXTI_PROPERTY_MASK (EXTI_CONFIG | EXTI_GPIO) + +/** + * @brief EXTI bit usage + */ +#define EXTI_PIN_MASK 0x0000001Fu + +/** + * @brief EXTI Mask for interrupt & event mode + */ +#define EXTI_MODE_MASK (EXTI_MODE_EVENT | EXTI_MODE_INTERRUPT) + +/** + * @brief EXTI Mask for trigger possibilities + */ +#define EXTI_TRIGGER_MASK (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) + +/** + * @brief EXTI Line number + */ +#if defined(EXTI_IMR_IM23) +#define EXTI_LINE_NB 24UL +#else +#define EXTI_LINE_NB 23UL +#endif /* EXTI_IMR_IM23 */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup EXTI_Private_Macros EXTI Private Macros + * @{ + */ +#define IS_EXTI_LINE(__EXTI_LINE__) ((((__EXTI_LINE__) & ~(EXTI_PROPERTY_MASK | EXTI_PIN_MASK)) == 0x00u) && \ + ((((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_CONFIG) || \ + (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_GPIO)) && \ + (((__EXTI_LINE__) & EXTI_PIN_MASK) < EXTI_LINE_NB)) + +#define IS_EXTI_MODE(__EXTI_LINE__) ((((__EXTI_LINE__) & EXTI_MODE_MASK) != 0x00u) && \ + (((__EXTI_LINE__) & ~EXTI_MODE_MASK) == 0x00u)) + +#define IS_EXTI_TRIGGER(__EXTI_LINE__) (((__EXTI_LINE__) & ~EXTI_TRIGGER_MASK) == 0x00u) + +#define IS_EXTI_PENDING_EDGE(__EXTI_LINE__) ((__EXTI_LINE__) == EXTI_TRIGGER_RISING_FALLING) + +#define IS_EXTI_CONFIG_LINE(__EXTI_LINE__) (((__EXTI_LINE__) & EXTI_CONFIG) != 0x00u) + +#if !defined (GPIOD) +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOH)) +#elif !defined (GPIOE) +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOD) || \ + ((__PORT__) == EXTI_GPIOH)) +#elif !defined (GPIOF) +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOD) || \ + ((__PORT__) == EXTI_GPIOE) || \ + ((__PORT__) == EXTI_GPIOH)) +#elif !defined (GPIOI) +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOD) || \ + ((__PORT__) == EXTI_GPIOE) || \ + ((__PORT__) == EXTI_GPIOF) || \ + ((__PORT__) == EXTI_GPIOG) || \ + ((__PORT__) == EXTI_GPIOH)) +#elif !defined (GPIOJ) +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOD) || \ + ((__PORT__) == EXTI_GPIOE) || \ + ((__PORT__) == EXTI_GPIOF) || \ + ((__PORT__) == EXTI_GPIOG) || \ + ((__PORT__) == EXTI_GPIOH) || \ + ((__PORT__) == EXTI_GPIOI)) +#else +#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ + ((__PORT__) == EXTI_GPIOB) || \ + ((__PORT__) == EXTI_GPIOC) || \ + ((__PORT__) == EXTI_GPIOD) || \ + ((__PORT__) == EXTI_GPIOE) || \ + ((__PORT__) == EXTI_GPIOF) || \ + ((__PORT__) == EXTI_GPIOG) || \ + ((__PORT__) == EXTI_GPIOH) || \ + ((__PORT__) == EXTI_GPIOI) || \ + ((__PORT__) == EXTI_GPIOJ) || \ + ((__PORT__) == EXTI_GPIOK)) +#endif /* GPIOD */ + +#define IS_EXTI_GPIO_PIN(__PIN__) ((__PIN__) < 16U) +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup EXTI_Exported_Functions EXTI Exported Functions + * @brief EXTI Exported Functions + * @{ + */ + +/** @defgroup EXTI_Exported_Functions_Group1 Configuration functions + * @brief Configuration functions + * @{ + */ +/* Configuration functions ****************************************************/ +HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); +HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); +HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti); +HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)); +HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine); +/** + * @} + */ + +/** @defgroup EXTI_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * @{ + */ +/* IO operation functions *****************************************************/ +void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti); +uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); +void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); +void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32f4xx_HAL_EXTI_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h index 26d789e..a047e82 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h @@ -1,425 +1,425 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash.h - * @author MCD Application Team - * @brief Header file of FLASH HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_H -#define __STM32F4xx_HAL_FLASH_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Procedure structure definition - */ -typedef enum -{ - FLASH_PROC_NONE = 0U, - FLASH_PROC_SECTERASE, - FLASH_PROC_MASSERASE, - FLASH_PROC_PROGRAM -} FLASH_ProcedureTypeDef; - -/** - * @brief FLASH handle Structure definition - */ -typedef struct -{ - __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/ - - __IO uint32_t NbSectorsToErase; /*Internal variable to save the remaining sectors to erase in IT context*/ - - __IO uint8_t VoltageForErase; /*Internal variable to provide voltage range selected by user in IT context*/ - - __IO uint32_t Sector; /*Internal variable to define the current sector which is erasing*/ - - __IO uint32_t Bank; /*Internal variable to save current bank selected during mass erase*/ - - __IO uint32_t Address; /*Internal variable to save address selected for program*/ - - HAL_LockTypeDef Lock; /* FLASH locking object */ - - __IO uint32_t ErrorCode; /* FLASH error code */ - -}FLASH_ProcessTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Constants FLASH Exported Constants - * @{ - */ -/** @defgroup FLASH_Error_Code FLASH Error Code - * @brief FLASH Error Code - * @{ - */ -#define HAL_FLASH_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_FLASH_ERROR_RD 0x00000001U /*!< Read Protection error */ -#define HAL_FLASH_ERROR_PGS 0x00000002U /*!< Programming Sequence error */ -#define HAL_FLASH_ERROR_PGP 0x00000004U /*!< Programming Parallelism error */ -#define HAL_FLASH_ERROR_PGA 0x00000008U /*!< Programming Alignment error */ -#define HAL_FLASH_ERROR_WRP 0x00000010U /*!< Write protection error */ -#define HAL_FLASH_ERROR_OPERATION 0x00000020U /*!< Operation Error */ -/** - * @} - */ - -/** @defgroup FLASH_Type_Program FLASH Type Program - * @{ - */ -#define FLASH_TYPEPROGRAM_BYTE 0x00000000U /*!< Program byte (8-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_HALFWORD 0x00000001U /*!< Program a half-word (16-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_WORD 0x00000002U /*!< Program a word (32-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_DOUBLEWORD 0x00000003U /*!< Program a double word (64-bit) at a specified address */ -/** - * @} - */ - -/** @defgroup FLASH_Flag_definition FLASH Flag definition - * @brief Flag definition - * @{ - */ -#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */ -#define FLASH_FLAG_OPERR FLASH_SR_SOP /*!< FLASH operation Error flag */ -#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */ -#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */ -#define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */ -#define FLASH_FLAG_PGSERR FLASH_SR_PGSERR /*!< FLASH Programming Sequence error flag */ -#if defined(FLASH_SR_RDERR) -#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< Read Protection error flag (PCROP) */ -#endif /* FLASH_SR_RDERR */ -#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */ -/** - * @} - */ - -/** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition - * @brief FLASH Interrupt definition - * @{ - */ -#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */ -#define FLASH_IT_ERR 0x02000000U /*!< Error Interrupt source */ -/** - * @} - */ - -/** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism - * @{ - */ -#define FLASH_PSIZE_BYTE 0x00000000U -#define FLASH_PSIZE_HALF_WORD 0x00000100U -#define FLASH_PSIZE_WORD 0x00000200U -#define FLASH_PSIZE_DOUBLE_WORD 0x00000300U -#define CR_PSIZE_MASK 0xFFFFFCFFU -/** - * @} - */ - -/** @defgroup FLASH_Keys FLASH Keys - * @{ - */ -#define RDP_KEY ((uint16_t)0x00A5) -#define FLASH_KEY1 0x45670123U -#define FLASH_KEY2 0xCDEF89ABU -#define FLASH_OPT_KEY1 0x08192A3BU -#define FLASH_OPT_KEY2 0x4C5D6E7FU -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Macros FLASH Exported Macros - * @{ - */ -/** - * @brief Set the FLASH Latency. - * @param __LATENCY__ FLASH Latency - * The value of this parameter depend on device used within the same series - * @retval none - */ -#define __HAL_FLASH_SET_LATENCY(__LATENCY__) (*(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)(__LATENCY__)) - -/** - * @brief Get the FLASH Latency. - * @retval FLASH Latency - * The value of this parameter depend on device used within the same series - */ -#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)) - -/** - * @brief Enable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN) - -/** - * @brief Disable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN)) - -/** - * @brief Enable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_ICEN) - -/** - * @brief Disable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_ICEN)) - -/** - * @brief Enable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_DCEN) - -/** - * @brief Disable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_DCEN)) - -/** - * @brief Resets the FLASH instruction Cache. - * @note This function must be used only when the Instruction Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_ICRST; \ - FLASH->ACR &= ~FLASH_ACR_ICRST; \ - }while(0U) - -/** - * @brief Resets the FLASH data Cache. - * @note This function must be used only when the data Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_DATA_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_DCRST; \ - FLASH->ACR &= ~FLASH_ACR_DCRST; \ - }while(0U) -/** - * @brief Enable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__)) - -/** - * @brief Get the specified FLASH flag status. - * @param __FLAG__ specifies the FLASH flags to check. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * @arg FLASH_FLAG_BSY : FLASH Busy flag - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__))) - -/** - * @brief Clear the specified FLASH flags. - * @param __FLAG__ specifies the FLASH flags to clear. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval none - */ -#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__)) -/** - * @} - */ - -/* Include FLASH HAL Extension module */ -#include "stm32f4xx_hal_flash_ex.h" -#include "stm32f4xx_hal_flash_ramfunc.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_Exported_Functions - * @{ - */ -/** @addtogroup FLASH_Exported_Functions_Group1 - * @{ - */ -/* Program operation functions ***********************************************/ -HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -/* FLASH IRQ handler method */ -void HAL_FLASH_IRQHandler(void); -/* Callbacks in non blocking modes */ -void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue); -void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions **********************************************/ -HAL_StatusTypeDef HAL_FLASH_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_Lock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Lock(void); -/* Option bytes control */ -HAL_StatusTypeDef HAL_FLASH_OB_Launch(void); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -uint32_t HAL_FLASH_GetError(void); -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Variables FLASH Private Variables - * @{ - */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Constants FLASH Private Constants - * @{ - */ - -/** - * @brief ACR register byte 0 (Bits[7:0]) base address - */ -#define ACR_BYTE0_ADDRESS 0x40023C00U -/** - * @brief OPTCR register byte 0 (Bits[7:0]) base address - */ -#define OPTCR_BYTE0_ADDRESS 0x40023C14U -/** - * @brief OPTCR register byte 1 (Bits[15:8]) base address - */ -#define OPTCR_BYTE1_ADDRESS 0x40023C15U -/** - * @brief OPTCR register byte 2 (Bits[23:16]) base address - */ -#define OPTCR_BYTE2_ADDRESS 0x40023C16U -/** - * @brief OPTCR register byte 3 (Bits[31:24]) base address - */ -#define OPTCR_BYTE3_ADDRESS 0x40023C17U - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FLASH_Private_Macros FLASH Private Macros - * @{ - */ - -/** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters - * @{ - */ -#define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \ - ((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD)) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Functions FLASH Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash.h + * @author MCD Application Team + * @brief Header file of FLASH HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_FLASH_H +#define __STM32F4xx_HAL_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup FLASH_Exported_Types FLASH Exported Types + * @{ + */ + +/** + * @brief FLASH Procedure structure definition + */ +typedef enum +{ + FLASH_PROC_NONE = 0U, + FLASH_PROC_SECTERASE, + FLASH_PROC_MASSERASE, + FLASH_PROC_PROGRAM +} FLASH_ProcedureTypeDef; + +/** + * @brief FLASH handle Structure definition + */ +typedef struct +{ + __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/ + + __IO uint32_t NbSectorsToErase; /*Internal variable to save the remaining sectors to erase in IT context*/ + + __IO uint8_t VoltageForErase; /*Internal variable to provide voltage range selected by user in IT context*/ + + __IO uint32_t Sector; /*Internal variable to define the current sector which is erasing*/ + + __IO uint32_t Bank; /*Internal variable to save current bank selected during mass erase*/ + + __IO uint32_t Address; /*Internal variable to save address selected for program*/ + + HAL_LockTypeDef Lock; /* FLASH locking object */ + + __IO uint32_t ErrorCode; /* FLASH error code */ + +}FLASH_ProcessTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup FLASH_Exported_Constants FLASH Exported Constants + * @{ + */ +/** @defgroup FLASH_Error_Code FLASH Error Code + * @brief FLASH Error Code + * @{ + */ +#define HAL_FLASH_ERROR_NONE 0x00000000U /*!< No error */ +#define HAL_FLASH_ERROR_RD 0x00000001U /*!< Read Protection error */ +#define HAL_FLASH_ERROR_PGS 0x00000002U /*!< Programming Sequence error */ +#define HAL_FLASH_ERROR_PGP 0x00000004U /*!< Programming Parallelism error */ +#define HAL_FLASH_ERROR_PGA 0x00000008U /*!< Programming Alignment error */ +#define HAL_FLASH_ERROR_WRP 0x00000010U /*!< Write protection error */ +#define HAL_FLASH_ERROR_OPERATION 0x00000020U /*!< Operation Error */ +/** + * @} + */ + +/** @defgroup FLASH_Type_Program FLASH Type Program + * @{ + */ +#define FLASH_TYPEPROGRAM_BYTE 0x00000000U /*!< Program byte (8-bit) at a specified address */ +#define FLASH_TYPEPROGRAM_HALFWORD 0x00000001U /*!< Program a half-word (16-bit) at a specified address */ +#define FLASH_TYPEPROGRAM_WORD 0x00000002U /*!< Program a word (32-bit) at a specified address */ +#define FLASH_TYPEPROGRAM_DOUBLEWORD 0x00000003U /*!< Program a double word (64-bit) at a specified address */ +/** + * @} + */ + +/** @defgroup FLASH_Flag_definition FLASH Flag definition + * @brief Flag definition + * @{ + */ +#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_OPERR FLASH_SR_SOP /*!< FLASH operation Error flag */ +#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */ +#define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */ +#define FLASH_FLAG_PGSERR FLASH_SR_PGSERR /*!< FLASH Programming Sequence error flag */ +#if defined(FLASH_SR_RDERR) +#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< Read Protection error flag (PCROP) */ +#endif /* FLASH_SR_RDERR */ +#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */ +/** + * @} + */ + +/** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition + * @brief FLASH Interrupt definition + * @{ + */ +#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */ +#define FLASH_IT_ERR 0x02000000U /*!< Error Interrupt source */ +/** + * @} + */ + +/** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism + * @{ + */ +#define FLASH_PSIZE_BYTE 0x00000000U +#define FLASH_PSIZE_HALF_WORD 0x00000100U +#define FLASH_PSIZE_WORD 0x00000200U +#define FLASH_PSIZE_DOUBLE_WORD 0x00000300U +#define CR_PSIZE_MASK 0xFFFFFCFFU +/** + * @} + */ + +/** @defgroup FLASH_Keys FLASH Keys + * @{ + */ +#define RDP_KEY ((uint16_t)0x00A5) +#define FLASH_KEY1 0x45670123U +#define FLASH_KEY2 0xCDEF89ABU +#define FLASH_OPT_KEY1 0x08192A3BU +#define FLASH_OPT_KEY2 0x4C5D6E7FU +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup FLASH_Exported_Macros FLASH Exported Macros + * @{ + */ +/** + * @brief Set the FLASH Latency. + * @param __LATENCY__ FLASH Latency + * The value of this parameter depend on device used within the same series + * @retval none + */ +#define __HAL_FLASH_SET_LATENCY(__LATENCY__) (*(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)(__LATENCY__)) + +/** + * @brief Get the FLASH Latency. + * @retval FLASH Latency + * The value of this parameter depend on device used within the same series + */ +#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)) + +/** + * @brief Enable the FLASH prefetch buffer. + * @retval none + */ +#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN) + +/** + * @brief Disable the FLASH prefetch buffer. + * @retval none + */ +#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN)) + +/** + * @brief Enable the FLASH instruction cache. + * @retval none + */ +#define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_ICEN) + +/** + * @brief Disable the FLASH instruction cache. + * @retval none + */ +#define __HAL_FLASH_INSTRUCTION_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_ICEN)) + +/** + * @brief Enable the FLASH data cache. + * @retval none + */ +#define __HAL_FLASH_DATA_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_DCEN) + +/** + * @brief Disable the FLASH data cache. + * @retval none + */ +#define __HAL_FLASH_DATA_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_DCEN)) + +/** + * @brief Resets the FLASH instruction Cache. + * @note This function must be used only when the Instruction Cache is disabled. + * @retval None + */ +#define __HAL_FLASH_INSTRUCTION_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_ICRST; \ + FLASH->ACR &= ~FLASH_ACR_ICRST; \ + }while(0U) + +/** + * @brief Resets the FLASH data Cache. + * @note This function must be used only when the data Cache is disabled. + * @retval None + */ +#define __HAL_FLASH_DATA_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_DCRST; \ + FLASH->ACR &= ~FLASH_ACR_DCRST; \ + }while(0U) +/** + * @brief Enable the specified FLASH interrupt. + * @param __INTERRUPT__ FLASH interrupt + * This parameter can be any combination of the following values: + * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt + * @arg FLASH_IT_ERR: Error Interrupt + * @retval none + */ +#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__)) + +/** + * @brief Disable the specified FLASH interrupt. + * @param __INTERRUPT__ FLASH interrupt + * This parameter can be any combination of the following values: + * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt + * @arg FLASH_IT_ERR: Error Interrupt + * @retval none + */ +#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__)) + +/** + * @brief Get the specified FLASH flag status. + * @param __FLAG__ specifies the FLASH flags to check. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_EOP : FLASH End of Operation flag + * @arg FLASH_FLAG_OPERR : FLASH operation Error flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag + * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag + * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag + * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) + * @arg FLASH_FLAG_BSY : FLASH Busy flag + * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices + * @retval The new state of __FLAG__ (SET or RESET). + */ +#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__))) + +/** + * @brief Clear the specified FLASH flags. + * @param __FLAG__ specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_EOP : FLASH End of Operation flag + * @arg FLASH_FLAG_OPERR : FLASH operation Error flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag + * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag + * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag + * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) + * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices + * @retval none + */ +#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__)) +/** + * @} + */ + +/* Include FLASH HAL Extension module */ +#include "stm32f4xx_hal_flash_ex.h" +#include "stm32f4xx_hal_flash_ramfunc.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup FLASH_Exported_Functions + * @{ + */ +/** @addtogroup FLASH_Exported_Functions_Group1 + * @{ + */ +/* Program operation functions ***********************************************/ +HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data); +HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data); +/* FLASH IRQ handler method */ +void HAL_FLASH_IRQHandler(void); +/* Callbacks in non blocking modes */ +void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue); +void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue); +/** + * @} + */ + +/** @addtogroup FLASH_Exported_Functions_Group2 + * @{ + */ +/* Peripheral Control functions **********************************************/ +HAL_StatusTypeDef HAL_FLASH_Unlock(void); +HAL_StatusTypeDef HAL_FLASH_Lock(void); +HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void); +HAL_StatusTypeDef HAL_FLASH_OB_Lock(void); +/* Option bytes control */ +HAL_StatusTypeDef HAL_FLASH_OB_Launch(void); +/** + * @} + */ + +/** @addtogroup FLASH_Exported_Functions_Group3 + * @{ + */ +/* Peripheral State functions ************************************************/ +uint32_t HAL_FLASH_GetError(void); +HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup FLASH_Private_Variables FLASH Private Variables + * @{ + */ + +/** + * @} + */ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup FLASH_Private_Constants FLASH Private Constants + * @{ + */ + +/** + * @brief ACR register byte 0 (Bits[7:0]) base address + */ +#define ACR_BYTE0_ADDRESS 0x40023C00U +/** + * @brief OPTCR register byte 0 (Bits[7:0]) base address + */ +#define OPTCR_BYTE0_ADDRESS 0x40023C14U +/** + * @brief OPTCR register byte 1 (Bits[15:8]) base address + */ +#define OPTCR_BYTE1_ADDRESS 0x40023C15U +/** + * @brief OPTCR register byte 2 (Bits[23:16]) base address + */ +#define OPTCR_BYTE2_ADDRESS 0x40023C16U +/** + * @brief OPTCR register byte 3 (Bits[31:24]) base address + */ +#define OPTCR_BYTE3_ADDRESS 0x40023C17U + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup FLASH_Private_Macros FLASH Private Macros + * @{ + */ + +/** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters + * @{ + */ +#define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \ + ((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \ + ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \ + ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD)) +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup FLASH_Private_Functions FLASH Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_FLASH_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h index 1cf8c45..908fd5e 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h @@ -1,1063 +1,1063 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ex.h - * @author MCD Application Team - * @brief Header file of FLASH HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_EX_H -#define __STM32F4xx_HAL_FLASH_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASHEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASHEx_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Erase structure definition - */ -typedef struct -{ - uint32_t TypeErase; /*!< Mass erase or sector Erase. - This parameter can be a value of @ref FLASHEx_Type_Erase */ - - uint32_t Banks; /*!< Select banks to erase when Mass erase is enabled. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t Sector; /*!< Initial FLASH sector to erase when Mass erase is disabled - This parameter must be a value of @ref FLASHEx_Sectors */ - - uint32_t NbSectors; /*!< Number of sectors to be erased. - This parameter must be a value between 1 and (max number of sectors - value of Initial sector)*/ - - uint32_t VoltageRange;/*!< The device voltage range which defines the erase parallelism - This parameter must be a value of @ref FLASHEx_Voltage_Range */ - -} FLASH_EraseInitTypeDef; - -/** - * @brief FLASH Option Bytes Program structure definition - */ -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured. - This parameter can be a value of @ref FLASHEx_Option_Type */ - - uint32_t WRPState; /*!< Write protection activation or deactivation. - This parameter can be a value of @ref FLASHEx_WRP_State */ - - uint32_t WRPSector; /*!< Specifies the sector(s) to be write protected. - The value of this parameter depend on device used within the same series */ - - uint32_t Banks; /*!< Select banks for WRP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t RDPLevel; /*!< Set the read protection level. - This parameter can be a value of @ref FLASHEx_Option_Bytes_Read_Protection */ - - uint32_t BORLevel; /*!< Set the BOR Level. - This parameter can be a value of @ref FLASHEx_BOR_Reset_Level */ - - uint8_t USERConfig; /*!< Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. */ - -} FLASH_OBProgramInitTypeDef; - -/** - * @brief FLASH Advanced Option Bytes Program structure definition - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured for extension. - This parameter can be a value of @ref FLASHEx_Advanced_Option_Type */ - - uint32_t PCROPState; /*!< PCROP activation or deactivation. - This parameter can be a value of @ref FLASHEx_PCROP_State */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - uint16_t Sectors; /*!< specifies the sector(s) set for PCROP. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx ||\ - STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Banks; /*!< Select banks for PCROP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint16_t SectorsBank1; /*!< Specifies the sector(s) set for PCROP for Bank1. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint16_t SectorsBank2; /*!< Specifies the sector(s) set for PCROP for Bank2. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint8_t BootConfig; /*!< Specifies Option bytes for boot config. - This parameter can be a value of @ref FLASHEx_Dual_Boot */ - -#endif /*STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -}FLASH_AdvOBProgramInitTypeDef; -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || - STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FLASHEx_Exported_Constants FLASH Exported Constants - * @{ - */ - -/** @defgroup FLASHEx_Type_Erase FLASH Type Erase - * @{ - */ -#define FLASH_TYPEERASE_SECTORS 0x00000000U /*!< Sectors erase only */ -#define FLASH_TYPEERASE_MASSERASE 0x00000001U /*!< Flash Mass erase activation */ -/** - * @} - */ - -/** @defgroup FLASHEx_Voltage_Range FLASH Voltage Range - * @{ - */ -#define FLASH_VOLTAGE_RANGE_1 0x00000000U /*!< Device operating range: 1.8V to 2.1V */ -#define FLASH_VOLTAGE_RANGE_2 0x00000001U /*!< Device operating range: 2.1V to 2.7V */ -#define FLASH_VOLTAGE_RANGE_3 0x00000002U /*!< Device operating range: 2.7V to 3.6V */ -#define FLASH_VOLTAGE_RANGE_4 0x00000003U /*!< Device operating range: 2.7V to 3.6V + External Vpp */ -/** - * @} - */ - -/** @defgroup FLASHEx_WRP_State FLASH WRP State - * @{ - */ -#define OB_WRPSTATE_DISABLE 0x00000000U /*!< Disable the write protection of the desired bank 1 sectors */ -#define OB_WRPSTATE_ENABLE 0x00000001U /*!< Enable the write protection of the desired bank 1 sectors */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Type FLASH Option Type - * @{ - */ -#define OPTIONBYTE_WRP 0x00000001U /*!< WRP option byte configuration */ -#define OPTIONBYTE_RDP 0x00000002U /*!< RDP option byte configuration */ -#define OPTIONBYTE_USER 0x00000004U /*!< USER option byte configuration */ -#define OPTIONBYTE_BOR 0x00000008U /*!< BOR option byte configuration */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_Read_Protection FLASH Option Bytes Read Protection - * @{ - */ -#define OB_RDP_LEVEL_0 ((uint8_t)0xAA) -#define OB_RDP_LEVEL_1 ((uint8_t)0x55) -#define OB_RDP_LEVEL_2 ((uint8_t)0xCC) /*!< Warning: When enabling read protection level 2 - it s no more possible to go back to level 1 or 0 */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_IWatchdog FLASH Option Bytes IWatchdog - * @{ - */ -#define OB_IWDG_SW ((uint8_t)0x20) /*!< Software IWDG selected */ -#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_nRST_STOP FLASH Option Bytes nRST_STOP - * @{ - */ -#define OB_STOP_NO_RST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */ -#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ -/** - * @} - */ - - -/** @defgroup FLASHEx_Option_Bytes_nRST_STDBY FLASH Option Bytes nRST_STDBY - * @{ - */ -#define OB_STDBY_NO_RST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */ -#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ -/** - * @} - */ - -/** @defgroup FLASHEx_BOR_Reset_Level FLASH BOR Reset Level - * @{ - */ -#define OB_BOR_LEVEL3 ((uint8_t)0x00) /*!< Supply voltage ranges from 2.70 to 3.60 V */ -#define OB_BOR_LEVEL2 ((uint8_t)0x04) /*!< Supply voltage ranges from 2.40 to 2.70 V */ -#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< Supply voltage ranges from 2.10 to 2.40 V */ -#define OB_BOR_OFF ((uint8_t)0x0C) /*!< Supply voltage ranges from 1.62 to 2.10 V */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup FLASHEx_PCROP_State FLASH PCROP State - * @{ - */ -#define OB_PCROP_STATE_DISABLE 0x00000000U /*!< Disable PCROP */ -#define OB_PCROP_STATE_ENABLE 0x00000001U /*!< Enable PCROP */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** @defgroup FLASHEx_Advanced_Option_Type FLASH Advanced Option Type - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!< PCROP option byte configuration */ -#define OPTIONBYTE_BOOTCONFIG 0x00000002U /*!< BOOTConfig option byte configuration */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) || \ - (((ADDRESS) >= FLASH_OTP_BASE) && ((ADDRESS) <= FLASH_OTP_END))) - -#define IS_FLASH_NBSECTORS(NBSECTORS) (((NBSECTORS) != 0) && ((NBSECTORS) <= FLASH_SECTOR_TOTAL)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFF000000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F401xC) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_BOOT(BOOT) (((BOOT) == OB_DUAL_BOOT_ENABLE) || ((BOOT) == OB_DUAL_BOOT_DISABLE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PCROP_SELECTED) || ((PCROP) == OB_PCROP_DESELECTED)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASHEx_Private_Functions FLASH Private Functions - * @{ - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange); -void FLASH_FlushCaches(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_EX_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ex.h + * @author MCD Application Team + * @brief Header file of FLASH HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_FLASH_EX_H +#define __STM32F4xx_HAL_FLASH_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup FLASHEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup FLASHEx_Exported_Types FLASH Exported Types + * @{ + */ + +/** + * @brief FLASH Erase structure definition + */ +typedef struct +{ + uint32_t TypeErase; /*!< Mass erase or sector Erase. + This parameter can be a value of @ref FLASHEx_Type_Erase */ + + uint32_t Banks; /*!< Select banks to erase when Mass erase is enabled. + This parameter must be a value of @ref FLASHEx_Banks */ + + uint32_t Sector; /*!< Initial FLASH sector to erase when Mass erase is disabled + This parameter must be a value of @ref FLASHEx_Sectors */ + + uint32_t NbSectors; /*!< Number of sectors to be erased. + This parameter must be a value between 1 and (max number of sectors - value of Initial sector)*/ + + uint32_t VoltageRange;/*!< The device voltage range which defines the erase parallelism + This parameter must be a value of @ref FLASHEx_Voltage_Range */ + +} FLASH_EraseInitTypeDef; + +/** + * @brief FLASH Option Bytes Program structure definition + */ +typedef struct +{ + uint32_t OptionType; /*!< Option byte to be configured. + This parameter can be a value of @ref FLASHEx_Option_Type */ + + uint32_t WRPState; /*!< Write protection activation or deactivation. + This parameter can be a value of @ref FLASHEx_WRP_State */ + + uint32_t WRPSector; /*!< Specifies the sector(s) to be write protected. + The value of this parameter depend on device used within the same series */ + + uint32_t Banks; /*!< Select banks for WRP activation/deactivation of all sectors. + This parameter must be a value of @ref FLASHEx_Banks */ + + uint32_t RDPLevel; /*!< Set the read protection level. + This parameter can be a value of @ref FLASHEx_Option_Bytes_Read_Protection */ + + uint32_t BORLevel; /*!< Set the BOR Level. + This parameter can be a value of @ref FLASHEx_BOR_Reset_Level */ + + uint8_t USERConfig; /*!< Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. */ + +} FLASH_OBProgramInitTypeDef; + +/** + * @brief FLASH Advanced Option Bytes Program structure definition + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +typedef struct +{ + uint32_t OptionType; /*!< Option byte to be configured for extension. + This parameter can be a value of @ref FLASHEx_Advanced_Option_Type */ + + uint32_t PCROPState; /*!< PCROP activation or deactivation. + This parameter can be a value of @ref FLASHEx_PCROP_State */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + uint16_t Sectors; /*!< specifies the sector(s) set for PCROP. + This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx ||\ + STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + uint32_t Banks; /*!< Select banks for PCROP activation/deactivation of all sectors. + This parameter must be a value of @ref FLASHEx_Banks */ + + uint16_t SectorsBank1; /*!< Specifies the sector(s) set for PCROP for Bank1. + This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ + + uint16_t SectorsBank2; /*!< Specifies the sector(s) set for PCROP for Bank2. + This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ + + uint8_t BootConfig; /*!< Specifies Option bytes for boot config. + This parameter can be a value of @ref FLASHEx_Dual_Boot */ + +#endif /*STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +}FLASH_AdvOBProgramInitTypeDef; +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || + STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup FLASHEx_Exported_Constants FLASH Exported Constants + * @{ + */ + +/** @defgroup FLASHEx_Type_Erase FLASH Type Erase + * @{ + */ +#define FLASH_TYPEERASE_SECTORS 0x00000000U /*!< Sectors erase only */ +#define FLASH_TYPEERASE_MASSERASE 0x00000001U /*!< Flash Mass erase activation */ +/** + * @} + */ + +/** @defgroup FLASHEx_Voltage_Range FLASH Voltage Range + * @{ + */ +#define FLASH_VOLTAGE_RANGE_1 0x00000000U /*!< Device operating range: 1.8V to 2.1V */ +#define FLASH_VOLTAGE_RANGE_2 0x00000001U /*!< Device operating range: 2.1V to 2.7V */ +#define FLASH_VOLTAGE_RANGE_3 0x00000002U /*!< Device operating range: 2.7V to 3.6V */ +#define FLASH_VOLTAGE_RANGE_4 0x00000003U /*!< Device operating range: 2.7V to 3.6V + External Vpp */ +/** + * @} + */ + +/** @defgroup FLASHEx_WRP_State FLASH WRP State + * @{ + */ +#define OB_WRPSTATE_DISABLE 0x00000000U /*!< Disable the write protection of the desired bank 1 sectors */ +#define OB_WRPSTATE_ENABLE 0x00000001U /*!< Enable the write protection of the desired bank 1 sectors */ +/** + * @} + */ + +/** @defgroup FLASHEx_Option_Type FLASH Option Type + * @{ + */ +#define OPTIONBYTE_WRP 0x00000001U /*!< WRP option byte configuration */ +#define OPTIONBYTE_RDP 0x00000002U /*!< RDP option byte configuration */ +#define OPTIONBYTE_USER 0x00000004U /*!< USER option byte configuration */ +#define OPTIONBYTE_BOR 0x00000008U /*!< BOR option byte configuration */ +/** + * @} + */ + +/** @defgroup FLASHEx_Option_Bytes_Read_Protection FLASH Option Bytes Read Protection + * @{ + */ +#define OB_RDP_LEVEL_0 ((uint8_t)0xAA) +#define OB_RDP_LEVEL_1 ((uint8_t)0x55) +#define OB_RDP_LEVEL_2 ((uint8_t)0xCC) /*!< Warning: When enabling read protection level 2 + it s no more possible to go back to level 1 or 0 */ +/** + * @} + */ + +/** @defgroup FLASHEx_Option_Bytes_IWatchdog FLASH Option Bytes IWatchdog + * @{ + */ +#define OB_IWDG_SW ((uint8_t)0x20) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ +/** + * @} + */ + +/** @defgroup FLASHEx_Option_Bytes_nRST_STOP FLASH Option Bytes nRST_STOP + * @{ + */ +#define OB_STOP_NO_RST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ +/** + * @} + */ + + +/** @defgroup FLASHEx_Option_Bytes_nRST_STDBY FLASH Option Bytes nRST_STDBY + * @{ + */ +#define OB_STDBY_NO_RST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ +/** + * @} + */ + +/** @defgroup FLASHEx_BOR_Reset_Level FLASH BOR Reset Level + * @{ + */ +#define OB_BOR_LEVEL3 ((uint8_t)0x00) /*!< Supply voltage ranges from 2.70 to 3.60 V */ +#define OB_BOR_LEVEL2 ((uint8_t)0x04) /*!< Supply voltage ranges from 2.40 to 2.70 V */ +#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< Supply voltage ranges from 2.10 to 2.40 V */ +#define OB_BOR_OFF ((uint8_t)0x0C) /*!< Supply voltage ranges from 1.62 to 2.10 V */ +/** + * @} + */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup FLASHEx_PCROP_State FLASH PCROP State + * @{ + */ +#define OB_PCROP_STATE_DISABLE 0x00000000U /*!< Disable PCROP */ +#define OB_PCROP_STATE_ENABLE 0x00000001U /*!< Enable PCROP */ +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ + STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +/** @defgroup FLASHEx_Advanced_Option_Type FLASH Advanced Option Type + * @{ + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +#define OPTIONBYTE_PCROP 0x00000001U /*!< PCROP option byte configuration */ +#define OPTIONBYTE_BOOTCONFIG 0x00000002U /*!< BOOTConfig option byte configuration */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +#define OPTIONBYTE_PCROP 0x00000001U /*!= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) || \ + (((ADDRESS) >= FLASH_OTP_BASE) && ((ADDRESS) <= FLASH_OTP_END))) + +#define IS_FLASH_NBSECTORS(NBSECTORS) (((NBSECTORS) != 0) && ((NBSECTORS) <= FLASH_SECTOR_TOTAL)) + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFF000000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F413xx) || defined(STM32F423xx) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F413xx || STM32F423xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F401xC) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F401xC */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ + defined(STM32F412Rx) || defined(STM32F412Cx) +#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F413xx) || defined(STM32F423xx) +#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F413xx || STM32F423xx */ + +#if defined(STM32F401xC) +#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F401xC */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ + defined(STM32F412Rx) || defined(STM32F412Cx) +#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) +#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +#define IS_OB_BOOT(BOOT) (((BOOT) == OB_DUAL_BOOT_ENABLE) || ((BOOT) == OB_DUAL_BOOT_DISABLE)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PCROP_SELECTED) || ((PCROP) == OB_PCROP_DESELECTED)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ + STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup FLASHEx_Private_Functions FLASH Private Functions + * @{ + */ +void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange); +void FLASH_FlushCaches(void); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_FLASH_EX_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h index 05917ec..b4d5f60 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h @@ -1,76 +1,76 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ramfunc.h - * @author MCD Application Team - * @brief Header file of FLASH RAMFUNC driver. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_FLASH_RAMFUNC_H -#define __STM32F4xx_FLASH_RAMFUNC_H - -#ifdef __cplusplus - extern "C" { -#endif -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_RAMFUNC_Exported_Functions - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1 - * @{ - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_FLASH_RAMFUNC_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ramfunc.h + * @author MCD Application Team + * @brief Header file of FLASH RAMFUNC driver. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_FLASH_RAMFUNC_H +#define __STM32F4xx_FLASH_RAMFUNC_H + +#ifdef __cplusplus + extern "C" { +#endif +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup FLASH_RAMFUNC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup FLASH_RAMFUNC_Exported_Functions + * @{ + */ + +/** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1 + * @{ + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void); +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void); +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void); +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +#ifdef __cplusplus +} +#endif + + +#endif /* __STM32F4xx_FLASH_RAMFUNC_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h index 5f3d749..661400f 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h @@ -1,325 +1,325 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_H -#define __STM32F4xx_HAL_GPIO_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup GPIO - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Types GPIO Exported Types - * @{ - */ - -/** - * @brief GPIO Init structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_pins_define */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_mode_define */ - - uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins. - This parameter can be a value of @ref GPIO_pull_define */ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_speed_define */ - - uint32_t Alternate; /*!< Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_Alternate_function_selection */ -}GPIO_InitTypeDef; - -/** - * @brief GPIO Bit SET and Bit RESET enumeration - */ -typedef enum -{ - GPIO_PIN_RESET = 0, - GPIO_PIN_SET -}GPIO_PinState; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup GPIO_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_pins_define GPIO pins define - * @{ - */ -#define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */ -#define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */ -#define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */ -#define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */ -#define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */ -#define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */ -#define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */ -#define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */ -#define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */ -#define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */ -#define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */ -#define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */ -#define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */ -#define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */ -#define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */ -#define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */ -#define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */ - -#define GPIO_PIN_MASK 0x0000FFFFU /* PIN mask for assert test */ -/** - * @} - */ - -/** @defgroup GPIO_mode_define GPIO mode define - * @brief GPIO Configuration Mode - * Elements values convention: 0x00WX00YZ - * - W : EXTI trigger detection on 3 bits - * - X : EXTI mode (IT or Event) on 2 bits - * - Y : Output type (Push Pull or Open Drain) on 1 bit - * - Z : GPIO mode (Input, Output, Alternate or Analog) on 2 bits - * @{ - */ -#define GPIO_MODE_INPUT MODE_INPUT /*!< Input Floating Mode */ -#define GPIO_MODE_OUTPUT_PP (MODE_OUTPUT | OUTPUT_PP) /*!< Output Push Pull Mode */ -#define GPIO_MODE_OUTPUT_OD (MODE_OUTPUT | OUTPUT_OD) /*!< Output Open Drain Mode */ -#define GPIO_MODE_AF_PP (MODE_AF | OUTPUT_PP) /*!< Alternate Function Push Pull Mode */ -#define GPIO_MODE_AF_OD (MODE_AF | OUTPUT_OD) /*!< Alternate Function Open Drain Mode */ - -#define GPIO_MODE_ANALOG MODE_ANALOG /*!< Analog Mode */ - -#define GPIO_MODE_IT_RISING (MODE_INPUT | EXTI_IT | TRIGGER_RISING) /*!< External Interrupt Mode with Rising edge trigger detection */ -#define GPIO_MODE_IT_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_FALLING) /*!< External Interrupt Mode with Falling edge trigger detection */ -#define GPIO_MODE_IT_RISING_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ - -#define GPIO_MODE_EVT_RISING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING) /*!< External Event Mode with Rising edge trigger detection */ -#define GPIO_MODE_EVT_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_FALLING) /*!< External Event Mode with Falling edge trigger detection */ -#define GPIO_MODE_EVT_RISING_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Event Mode with Rising/Falling edge trigger detection */ - -/** - * @} - */ - -/** @defgroup GPIO_speed_define GPIO speed define - * @brief GPIO Output Maximum frequency - * @{ - */ -#define GPIO_SPEED_FREQ_LOW 0x00000000U /*!< IO works at 2 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_MEDIUM 0x00000001U /*!< range 12,5 MHz to 50 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_HIGH 0x00000002U /*!< range 25 MHz to 100 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_VERY_HIGH 0x00000003U /*!< range 50 MHz to 200 MHz, please refer to the product datasheet */ -/** - * @} - */ - - /** @defgroup GPIO_pull_define GPIO pull define - * @brief GPIO Pull-Up or Pull-Down Activation - * @{ - */ -#define GPIO_NOPULL 0x00000000U /*!< No Pull-up or Pull-down activation */ -#define GPIO_PULLUP 0x00000001U /*!< Pull-up activation */ -#define GPIO_PULLDOWN 0x00000002U /*!< Pull-down activation */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** - * @brief Checks whether the specified EXTI line flag is set or not. - * @param __EXTI_LINE__ specifies the EXTI line flag to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending flags. - * @param __EXTI_LINE__ specifies the EXTI lines flags to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Checks whether the specified EXTI line is asserted or not. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending bits. - * @param __EXTI_LINE__ specifies the EXTI lines to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Generates a Software interrupt on selected EXTI line. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__)) -/** - * @} - */ - -/* Include GPIO HAL Extension module */ -#include "stm32f4xx_hal_gpio_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup GPIO_Exported_Functions - * @{ - */ - -/** @addtogroup GPIO_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init); -void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin); -/** - * @} - */ - -/** @addtogroup GPIO_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState); -void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Constants GPIO Private Constants - * @{ - */ -#define GPIO_MODE_Pos 0U -#define GPIO_MODE (0x3UL << GPIO_MODE_Pos) -#define MODE_INPUT (0x0UL << GPIO_MODE_Pos) -#define MODE_OUTPUT (0x1UL << GPIO_MODE_Pos) -#define MODE_AF (0x2UL << GPIO_MODE_Pos) -#define MODE_ANALOG (0x3UL << GPIO_MODE_Pos) -#define OUTPUT_TYPE_Pos 4U -#define OUTPUT_TYPE (0x1UL << OUTPUT_TYPE_Pos) -#define OUTPUT_PP (0x0UL << OUTPUT_TYPE_Pos) -#define OUTPUT_OD (0x1UL << OUTPUT_TYPE_Pos) -#define EXTI_MODE_Pos 16U -#define EXTI_MODE (0x3UL << EXTI_MODE_Pos) -#define EXTI_IT (0x1UL << EXTI_MODE_Pos) -#define EXTI_EVT (0x2UL << EXTI_MODE_Pos) -#define TRIGGER_MODE_Pos 20U -#define TRIGGER_MODE (0x7UL << TRIGGER_MODE_Pos) -#define TRIGGER_RISING (0x1UL << TRIGGER_MODE_Pos) -#define TRIGGER_FALLING (0x2UL << TRIGGER_MODE_Pos) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIO_Private_Macros GPIO Private Macros - * @{ - */ -#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET)) -#define IS_GPIO_PIN(PIN) (((((uint32_t)PIN) & GPIO_PIN_MASK ) != 0x00U) && ((((uint32_t)PIN) & ~GPIO_PIN_MASK) == 0x00U)) -#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\ - ((MODE) == GPIO_MODE_OUTPUT_PP) ||\ - ((MODE) == GPIO_MODE_OUTPUT_OD) ||\ - ((MODE) == GPIO_MODE_AF_PP) ||\ - ((MODE) == GPIO_MODE_AF_OD) ||\ - ((MODE) == GPIO_MODE_IT_RISING) ||\ - ((MODE) == GPIO_MODE_IT_FALLING) ||\ - ((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING) ||\ - ((MODE) == GPIO_MODE_EVT_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_ANALOG)) -#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_FREQ_LOW) || ((SPEED) == GPIO_SPEED_FREQ_MEDIUM) || \ - ((SPEED) == GPIO_SPEED_FREQ_HIGH) || ((SPEED) == GPIO_SPEED_FREQ_VERY_HIGH)) -#define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \ - ((PULL) == GPIO_PULLDOWN)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_gpio.h + * @author MCD Application Team + * @brief Header file of GPIO HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_GPIO_H +#define __STM32F4xx_HAL_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup GPIO_Exported_Types GPIO Exported Types + * @{ + */ + +/** + * @brief GPIO Init structure definition + */ +typedef struct +{ + uint32_t Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + uint32_t Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIO_mode_define */ + + uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins. + This parameter can be a value of @ref GPIO_pull_define */ + + uint32_t Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIO_speed_define */ + + uint32_t Alternate; /*!< Peripheral to be connected to the selected pins. + This parameter can be a value of @ref GPIO_Alternate_function_selection */ +}GPIO_InitTypeDef; + +/** + * @brief GPIO Bit SET and Bit RESET enumeration + */ +typedef enum +{ + GPIO_PIN_RESET = 0, + GPIO_PIN_SET +}GPIO_PinState; +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup GPIO_Exported_Constants GPIO Exported Constants + * @{ + */ + +/** @defgroup GPIO_pins_define GPIO pins define + * @{ + */ +#define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */ +#define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */ +#define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */ +#define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */ +#define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */ +#define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */ +#define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */ +#define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */ +#define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */ +#define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */ +#define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */ +#define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */ +#define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */ +#define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */ +#define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */ +#define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */ +#define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */ + +#define GPIO_PIN_MASK 0x0000FFFFU /* PIN mask for assert test */ +/** + * @} + */ + +/** @defgroup GPIO_mode_define GPIO mode define + * @brief GPIO Configuration Mode + * Elements values convention: 0x00WX00YZ + * - W : EXTI trigger detection on 3 bits + * - X : EXTI mode (IT or Event) on 2 bits + * - Y : Output type (Push Pull or Open Drain) on 1 bit + * - Z : GPIO mode (Input, Output, Alternate or Analog) on 2 bits + * @{ + */ +#define GPIO_MODE_INPUT MODE_INPUT /*!< Input Floating Mode */ +#define GPIO_MODE_OUTPUT_PP (MODE_OUTPUT | OUTPUT_PP) /*!< Output Push Pull Mode */ +#define GPIO_MODE_OUTPUT_OD (MODE_OUTPUT | OUTPUT_OD) /*!< Output Open Drain Mode */ +#define GPIO_MODE_AF_PP (MODE_AF | OUTPUT_PP) /*!< Alternate Function Push Pull Mode */ +#define GPIO_MODE_AF_OD (MODE_AF | OUTPUT_OD) /*!< Alternate Function Open Drain Mode */ + +#define GPIO_MODE_ANALOG MODE_ANALOG /*!< Analog Mode */ + +#define GPIO_MODE_IT_RISING (MODE_INPUT | EXTI_IT | TRIGGER_RISING) /*!< External Interrupt Mode with Rising edge trigger detection */ +#define GPIO_MODE_IT_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_FALLING) /*!< External Interrupt Mode with Falling edge trigger detection */ +#define GPIO_MODE_IT_RISING_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ + +#define GPIO_MODE_EVT_RISING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING) /*!< External Event Mode with Rising edge trigger detection */ +#define GPIO_MODE_EVT_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_FALLING) /*!< External Event Mode with Falling edge trigger detection */ +#define GPIO_MODE_EVT_RISING_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Event Mode with Rising/Falling edge trigger detection */ + +/** + * @} + */ + +/** @defgroup GPIO_speed_define GPIO speed define + * @brief GPIO Output Maximum frequency + * @{ + */ +#define GPIO_SPEED_FREQ_LOW 0x00000000U /*!< IO works at 2 MHz, please refer to the product datasheet */ +#define GPIO_SPEED_FREQ_MEDIUM 0x00000001U /*!< range 12,5 MHz to 50 MHz, please refer to the product datasheet */ +#define GPIO_SPEED_FREQ_HIGH 0x00000002U /*!< range 25 MHz to 100 MHz, please refer to the product datasheet */ +#define GPIO_SPEED_FREQ_VERY_HIGH 0x00000003U /*!< range 50 MHz to 200 MHz, please refer to the product datasheet */ +/** + * @} + */ + + /** @defgroup GPIO_pull_define GPIO pull define + * @brief GPIO Pull-Up or Pull-Down Activation + * @{ + */ +#define GPIO_NOPULL 0x00000000U /*!< No Pull-up or Pull-down activation */ +#define GPIO_PULLUP 0x00000001U /*!< Pull-up activation */ +#define GPIO_PULLDOWN 0x00000002U /*!< Pull-down activation */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup GPIO_Exported_Macros GPIO Exported Macros + * @{ + */ + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param __EXTI_LINE__ specifies the EXTI line flag to check. + * This parameter can be GPIO_PIN_x where x can be(0..15) + * @retval The new state of __EXTI_LINE__ (SET or RESET). + */ +#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) + +/** + * @brief Clears the EXTI's line pending flags. + * @param __EXTI_LINE__ specifies the EXTI lines flags to clear. + * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) + * @retval None + */ +#define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param __EXTI_LINE__ specifies the EXTI line to check. + * This parameter can be GPIO_PIN_x where x can be(0..15) + * @retval The new state of __EXTI_LINE__ (SET or RESET). + */ +#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) + +/** + * @brief Clears the EXTI's line pending bits. + * @param __EXTI_LINE__ specifies the EXTI lines to clear. + * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) + * @retval None + */ +#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) + +/** + * @brief Generates a Software interrupt on selected EXTI line. + * @param __EXTI_LINE__ specifies the EXTI line to check. + * This parameter can be GPIO_PIN_x where x can be(0..15) + * @retval None + */ +#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__)) +/** + * @} + */ + +/* Include GPIO HAL Extension module */ +#include "stm32f4xx_hal_gpio_ex.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup GPIO_Exported_Functions + * @{ + */ + +/** @addtogroup GPIO_Exported_Functions_Group1 + * @{ + */ +/* Initialization and de-initialization functions *****************************/ +void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init); +void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin); +/** + * @} + */ + +/** @addtogroup GPIO_Exported_Functions_Group2 + * @{ + */ +/* IO operation functions *****************************************************/ +GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState); +void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin); +void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin); + +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup GPIO_Private_Constants GPIO Private Constants + * @{ + */ +#define GPIO_MODE_Pos 0U +#define GPIO_MODE (0x3UL << GPIO_MODE_Pos) +#define MODE_INPUT (0x0UL << GPIO_MODE_Pos) +#define MODE_OUTPUT (0x1UL << GPIO_MODE_Pos) +#define MODE_AF (0x2UL << GPIO_MODE_Pos) +#define MODE_ANALOG (0x3UL << GPIO_MODE_Pos) +#define OUTPUT_TYPE_Pos 4U +#define OUTPUT_TYPE (0x1UL << OUTPUT_TYPE_Pos) +#define OUTPUT_PP (0x0UL << OUTPUT_TYPE_Pos) +#define OUTPUT_OD (0x1UL << OUTPUT_TYPE_Pos) +#define EXTI_MODE_Pos 16U +#define EXTI_MODE (0x3UL << EXTI_MODE_Pos) +#define EXTI_IT (0x1UL << EXTI_MODE_Pos) +#define EXTI_EVT (0x2UL << EXTI_MODE_Pos) +#define TRIGGER_MODE_Pos 20U +#define TRIGGER_MODE (0x7UL << TRIGGER_MODE_Pos) +#define TRIGGER_RISING (0x1UL << TRIGGER_MODE_Pos) +#define TRIGGER_FALLING (0x2UL << TRIGGER_MODE_Pos) + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup GPIO_Private_Macros GPIO Private Macros + * @{ + */ +#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET)) +#define IS_GPIO_PIN(PIN) (((((uint32_t)PIN) & GPIO_PIN_MASK ) != 0x00U) && ((((uint32_t)PIN) & ~GPIO_PIN_MASK) == 0x00U)) +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\ + ((MODE) == GPIO_MODE_OUTPUT_PP) ||\ + ((MODE) == GPIO_MODE_OUTPUT_OD) ||\ + ((MODE) == GPIO_MODE_AF_PP) ||\ + ((MODE) == GPIO_MODE_AF_OD) ||\ + ((MODE) == GPIO_MODE_IT_RISING) ||\ + ((MODE) == GPIO_MODE_IT_FALLING) ||\ + ((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\ + ((MODE) == GPIO_MODE_EVT_RISING) ||\ + ((MODE) == GPIO_MODE_EVT_FALLING) ||\ + ((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\ + ((MODE) == GPIO_MODE_ANALOG)) +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_FREQ_LOW) || ((SPEED) == GPIO_SPEED_FREQ_MEDIUM) || \ + ((SPEED) == GPIO_SPEED_FREQ_HIGH) || ((SPEED) == GPIO_SPEED_FREQ_VERY_HIGH)) +#define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \ + ((PULL) == GPIO_PULLDOWN)) +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup GPIO_Private_Functions GPIO Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_GPIO_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h index 5e0b7cc..393f388 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h @@ -1,1590 +1,1590 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio_ex.h - * @author MCD Application Team - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_EX_H -#define __STM32F4xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -/** @brief GPIO_Legacy - */ -#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_DFSDM2 ((uint8_t)0x03) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SAI1 ((uint8_t)0x07) /* SAI1 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ -#define GPIO_AF7_DFSDM2 ((uint8_t)0x07) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_SAI1 ((uint8_t)0x0A) /* SAI1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_DFSDM2 ((uint8_t)0x0A) /* DFSDM2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FSMC ((uint8_t)0x0A) /* FSMC Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_UART4 ((uint8_t)0x0B) /* UART4 Alternate Function mapping */ -#define GPIO_AF11_UART5 ((uint8_t)0x0B) /* UART5 Alternate Function mapping */ -#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ -#define GPIO_AF11_UART10 ((uint8_t)0x0B) /* UART10 Alternate Function mapping */ -#define GPIO_AF11_CAN3 ((uint8_t)0x0B) /* CAN3 Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_RNG ((uint8_t)0x0E) /* RNG Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F413xx || STM32F423xx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F411xE */ - -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI1 ((uint8_t)0x06) /* SPI1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F446xx -----------------------*/ -#if defined(STM32F446xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_CEC ((uint8_t)0x03) /* CEC Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_UART5 ((uint8_t)0x07) /* UART5 Alternate Function mapping */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SPDIFRX ((uint8_t)0x07) /* SPDIFRX Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_SPDIFRX ((uint8_t)0x08) /* SPDIFRX Alternate Function mapping */ -#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U : 8U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U :\ - ((__GPIOx__) == (GPIOJ))? 9U : 10U) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U : 7U) -#endif /* STM32F446xx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F412Vx */ -#if defined(STM32F412Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U : 7U) -#endif /* STM32F412Rx */ -#if defined(STM32F412Cx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F412Cx */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC)) - -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) - -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM9) || \ - ((AF) == GPIO_AF3_TIM10) || ((AF) == GPIO_AF3_TIM11) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF7_USART1) || \ - ((AF) == GPIO_AF7_USART2) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF15_EVENTOUT)) -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------------------- STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ - ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ - ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ - ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ - ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ - ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_EX_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_gpio_ex.h + * @author MCD Application Team + * @brief Header file of GPIO HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_GPIO_EX_H +#define __STM32F4xx_HAL_GPIO_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup GPIOEx GPIOEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants + * @{ + */ + +/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection + * @{ + */ + +/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ +#if defined(STM32F429xx) || defined(STM32F439xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ +#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ +#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ +#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ +#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ + +/** + * @brief AF 14 selection + */ +#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F429xx || STM32F439xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ +#if defined(STM32F427xx) || defined(STM32F437xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ +#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ +#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ +/** @brief GPIO_Legacy + */ +#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ +#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ +#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F427xx || STM32F437xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ +#if defined(STM32F407xx) || defined(STM32F417xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F407xx || STM32F417xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F405xx || STM32F415xx */ + +/*----------------------------------------------------------------------------*/ + +/*---------------------------------------- STM32F401xx------------------------*/ +#if defined(STM32F401xC) || defined(STM32F401xE) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ + + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F401xC || STM32F401xE */ +/*----------------------------------------------------------------------------*/ + +/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ +#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ +#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ +#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ +#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ +#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ +#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ +#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +/*----------------------------------------------------------------------------*/ + +/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ +#if defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ +#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ +#define GPIO_AF3_DFSDM2 ((uint8_t)0x03) /* DFSDM2 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ +#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ +#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ +#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF7_SAI1 ((uint8_t)0x07) /* SAI1 Alternate Function mapping */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ +#define GPIO_AF7_DFSDM2 ((uint8_t)0x07) /* DFSDM2 Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ +#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ +#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ +#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_SAI1 ((uint8_t)0x0A) /* SAI1 Alternate Function mapping */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF10_DFSDM2 ((uint8_t)0x0A) /* DFSDM2 Alternate Function mapping */ +#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ +#define GPIO_AF10_FSMC ((uint8_t)0x0A) /* FSMC Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_UART4 ((uint8_t)0x0B) /* UART4 Alternate Function mapping */ +#define GPIO_AF11_UART5 ((uint8_t)0x0B) /* UART5 Alternate Function mapping */ +#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ +#define GPIO_AF11_UART10 ((uint8_t)0x0B) /* UART10 Alternate Function mapping */ +#define GPIO_AF11_CAN3 ((uint8_t)0x0B) /* CAN3 Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ +#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ + +/** + * @brief AF 14 selection + */ +#define GPIO_AF14_RNG ((uint8_t)0x0E) /* RNG Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F413xx || STM32F423xx */ + +/*---------------------------------------- STM32F411xx------------------------*/ +#if defined(STM32F411xE) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ +#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F411xE */ + +/*---------------------------------------- STM32F410xx------------------------*/ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ +#if defined(STM32F410Cx) || defined(STM32F410Rx) +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#endif /* STM32F410Cx || STM32F410Rx */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI1 ((uint8_t)0x06) /* SPI1 Alternate Function mapping */ +#if defined(STM32F410Cx) || defined(STM32F410Rx) +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ +#endif /* STM32F410Cx || STM32F410Rx */ +#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ +#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +/*---------------------------------------- STM32F446xx -----------------------*/ +#if defined(STM32F446xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ +#define GPIO_AF3_CEC ((uint8_t)0x03) /* CEC Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ +#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ +#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping */ +#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_UART5 ((uint8_t)0x07) /* UART5 Alternate Function mapping */ +#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF7_SPDIFRX ((uint8_t)0x07) /* SPDIFRX Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_SPDIFRX ((uint8_t)0x08) /* SPDIFRX Alternate Function mapping */ +#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ +#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ +#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ + +#endif /* STM32F446xx */ +/*----------------------------------------------------------------------------*/ + +/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ +#if defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ +#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ +#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ +#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ +#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ +#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ +#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ +#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ +#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ +#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ +#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ +#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ + +/** + * @brief AF 14 selection + */ +#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ + +#endif /* STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros + * @{ + */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions + * @{ + */ +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Constants GPIO Private Constants + * @{ + */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Macros GPIO Private Macros + * @{ + */ +/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index + * @{ + */ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U :\ + ((__GPIOx__) == (GPIOF))? 5U :\ + ((__GPIOx__) == (GPIOG))? 6U :\ + ((__GPIOx__) == (GPIOH))? 7U : 8U) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U :\ + ((__GPIOx__) == (GPIOF))? 5U :\ + ((__GPIOx__) == (GPIOG))? 6U :\ + ((__GPIOx__) == (GPIOH))? 7U :\ + ((__GPIOx__) == (GPIOI))? 8U :\ + ((__GPIOx__) == (GPIOJ))? 9U : 10U) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U : 7U) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U : 7U) +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ + +#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U :\ + ((__GPIOx__) == (GPIOF))? 5U :\ + ((__GPIOx__) == (GPIOG))? 6U : 7U) +#endif /* STM32F446xx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U : 7U) +#endif /* STM32F412Vx */ +#if defined(STM32F412Rx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U : 7U) +#endif /* STM32F412Rx */ +#if defined(STM32F412Cx) +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U : 7U) +#endif /* STM32F412Cx */ + +/** + * @} + */ + +/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function + * @{ + */ +/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ +#if defined(STM32F429xx) || defined(STM32F439xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ + ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ + ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ + ((AF) == GPIO_AF14_LTDC)) + +#endif /* STM32F429xx || STM32F439xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ +#if defined(STM32F427xx) || defined(STM32F437xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ + ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ + ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) + +#endif /* STM32F427xx || STM32F437xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ +#if defined(STM32F407xx) || defined(STM32F417xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) + +#endif /* STM32F407xx || STM32F417xx */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) + +#endif /* STM32F405xx || STM32F415xx */ + +/*----------------------------------------------------------------------------*/ + +/*---------------------------------------- STM32F401xx------------------------*/ +#if defined(STM32F401xC) || defined(STM32F401xE) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF12_SDIO) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM9) || \ + ((AF) == GPIO_AF3_TIM10) || ((AF) == GPIO_AF3_TIM11) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF7_USART1) || \ + ((AF) == GPIO_AF7_USART2) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF15_EVENTOUT)) +#endif /* STM32F401xC || STM32F401xE */ +/*----------------------------------------------------------------------------*/ +/*---------------------------------------- STM32F410xx------------------------*/ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +/*---------------------------------------- STM32F411xx------------------------*/ +#if defined(STM32F411xE) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ + ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ + ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ + ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ + ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) + +#endif /* STM32F411xE */ +/*----------------------------------------------------------------------------*/ + +/*----------------------------------------------- STM32F446xx ----------------*/ +#if defined(STM32F446xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ + ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ + ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ + ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ + ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ + ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ + ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ + ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) + +#endif /* STM32F446xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ +#if defined(STM32F469xx) || defined(STM32F479xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ + ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ + ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ + ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ + ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ + ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) + +#endif /* STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) +#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +/*----------------------------------------------------------------------------*/ + +/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ +#if defined(STM32F413xx) || defined(STM32F423xx) +#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) +#endif /* STM32F413xx || STM32F423xx */ +/*----------------------------------------------------------------------------*/ + +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Functions GPIO Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_GPIO_EX_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h index 9a7a67e..b37126e 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h @@ -1,741 +1,741 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c.h - * @author MCD Application Team - * @brief Header file of I2C HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_H -#define __STM32F4xx_HAL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2C - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup I2C_Exported_Types I2C Exported Types - * @{ - */ - -/** @defgroup I2C_Configuration_Structure_definition I2C Configuration Structure definition - * @brief I2C Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref I2C_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref I2C_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref I2C_general_call_addressing_mode */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref I2C_nostretch_mode */ - -} I2C_InitTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_state_structure_definition HAL state structure definition - * @brief HAL State structure definition - * @note HAL I2C State value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : Abort (Abort user request on going) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized and ready to use. HAL I2C Init function called) - * b4 (not used) - * x : Should be set to 0 - * b3 - * 0 : Ready or Busy (No Listen mode ongoing) - * 1 : Listen (Peripheral in Address Listen Mode) - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * @{ - */ -typedef enum -{ - HAL_I2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_I2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_I2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_I2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_I2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_I2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_I2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */ - -} HAL_I2C_StateTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_mode_structure_definition HAL mode structure definition - * @brief HAL Mode structure definition - * @note HAL I2C Mode value coding follow below described bitmap :\n - * b7 (not used)\n - * x : Should be set to 0\n - * b6\n - * 0 : None\n - * 1 : Memory (HAL I2C communication is in Memory Mode)\n - * b5\n - * 0 : None\n - * 1 : Slave (HAL I2C communication is in Slave Mode)\n - * b4\n - * 0 : None\n - * 1 : Master (HAL I2C communication is in Master Mode)\n - * b3-b2-b1-b0 (not used)\n - * xxxx : Should be set to 0000 - * @{ - */ -typedef enum -{ - HAL_I2C_MODE_NONE = 0x00U, /*!< No I2C communication on going */ - HAL_I2C_MODE_MASTER = 0x10U, /*!< I2C communication is in Master Mode */ - HAL_I2C_MODE_SLAVE = 0x20U, /*!< I2C communication is in Slave Mode */ - HAL_I2C_MODE_MEM = 0x40U /*!< I2C communication is in Memory Mode */ - -} HAL_I2C_ModeTypeDef; - -/** - * @} - */ - -/** @defgroup I2C_Error_Code_definition I2C Error Code definition - * @brief I2C Error Code definition - * @{ - */ -#define HAL_I2C_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_I2C_ERROR_BERR 0x00000001U /*!< BERR error */ -#define HAL_I2C_ERROR_ARLO 0x00000002U /*!< ARLO error */ -#define HAL_I2C_ERROR_AF 0x00000004U /*!< AF error */ -#define HAL_I2C_ERROR_OVR 0x00000008U /*!< OVR error */ -#define HAL_I2C_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#define HAL_I2C_ERROR_TIMEOUT 0x00000020U /*!< Timeout Error */ -#define HAL_I2C_ERROR_SIZE 0x00000040U /*!< Size Management error */ -#define HAL_I2C_ERROR_DMA_PARAM 0x00000080U /*!< DMA Parameter Error */ -#define HAL_I2C_WRONG_START 0x00000200U /*!< Wrong start Error */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define HAL_I2C_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid Callback error */ -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup I2C_handle_Structure_definition I2C handle Structure definition - * @brief I2C handle Structure definition - * @{ - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -typedef struct __I2C_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -{ - I2C_TypeDef *Instance; /*!< I2C registers base address */ - - I2C_InitTypeDef Init; /*!< I2C communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */ - - uint16_t XferSize; /*!< I2C transfer size */ - - __IO uint16_t XferCount; /*!< I2C transfer counter */ - - __IO uint32_t XferOptions; /*!< I2C transfer options */ - - __IO uint32_t PreviousState; /*!< I2C communication Previous state and mode - context for internal usage */ - - DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< I2C locking object */ - - __IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */ - - __IO HAL_I2C_ModeTypeDef Mode; /*!< I2C communication mode */ - - __IO uint32_t ErrorCode; /*!< I2C Error code */ - - __IO uint32_t Devaddress; /*!< I2C Target device address */ - - __IO uint32_t Memaddress; /*!< I2C Target memory address */ - - __IO uint32_t MemaddSize; /*!< I2C Target memory address size */ - - __IO uint32_t EventCount; /*!< I2C Event counter */ - - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Listen Complete callback */ - void (* MemTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Error callback */ - void (* AbortCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Abort callback */ - - void (* AddrCallback)(struct __I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< I2C Slave Address Match callback */ - - void (* MspInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp Init callback */ - void (* MspDeInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp DeInit callback */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -} I2C_HandleTypeDef; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -/** - * @brief HAL I2C Callback ID enumeration definition - */ -typedef enum -{ - HAL_I2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< I2C Master Tx Transfer completed callback ID */ - HAL_I2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< I2C Master Rx Transfer completed callback ID */ - HAL_I2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< I2C Slave Tx Transfer completed callback ID */ - HAL_I2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< I2C Slave Rx Transfer completed callback ID */ - HAL_I2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< I2C Listen Complete callback ID */ - HAL_I2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< I2C Memory Tx Transfer callback ID */ - HAL_I2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< I2C Memory Rx Transfer completed callback ID */ - HAL_I2C_ERROR_CB_ID = 0x07U, /*!< I2C Error callback ID */ - HAL_I2C_ABORT_CB_ID = 0x08U, /*!< I2C Abort callback ID */ - - HAL_I2C_MSPINIT_CB_ID = 0x09U, /*!< I2C Msp Init callback ID */ - HAL_I2C_MSPDEINIT_CB_ID = 0x0AU /*!< I2C Msp DeInit callback ID */ - -} HAL_I2C_CallbackIDTypeDef; - -/** - * @brief HAL I2C Callback pointer definition - */ -typedef void (*pI2C_CallbackTypeDef)(I2C_HandleTypeDef *hi2c); /*!< pointer to an I2C callback function */ -typedef void (*pI2C_AddrCallbackTypeDef)(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_duty_cycle_in_fast_mode I2C duty cycle in fast mode - * @{ - */ -#define I2C_DUTYCYCLE_2 0x00000000U -#define I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY -/** - * @} - */ - -/** @defgroup I2C_addressing_mode I2C addressing mode - * @{ - */ -#define I2C_ADDRESSINGMODE_7BIT 0x00004000U -#define I2C_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) -/** - * @} - */ - -/** @defgroup I2C_dual_addressing_mode I2C dual addressing mode - * @{ - */ -#define I2C_DUALADDRESS_DISABLE 0x00000000U -#define I2C_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL -/** - * @} - */ - -/** @defgroup I2C_general_call_addressing_mode I2C general call addressing mode - * @{ - */ -#define I2C_GENERALCALL_DISABLE 0x00000000U -#define I2C_GENERALCALL_ENABLE I2C_CR1_ENGC -/** - * @} - */ - -/** @defgroup I2C_nostretch_mode I2C nostretch mode - * @{ - */ -#define I2C_NOSTRETCH_DISABLE 0x00000000U -#define I2C_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup I2C_Memory_Address_Size I2C Memory Address Size - * @{ - */ -#define I2C_MEMADD_SIZE_8BIT 0x00000001U -#define I2C_MEMADD_SIZE_16BIT 0x00000010U -/** - * @} - */ - -/** @defgroup I2C_XferDirection_definition I2C XferDirection definition - * @{ - */ -#define I2C_DIRECTION_RECEIVE 0x00000000U -#define I2C_DIRECTION_TRANSMIT 0x00000001U -/** - * @} - */ - -/** @defgroup I2C_XferOptions_definition I2C XferOptions definition - * @{ - */ -#define I2C_FIRST_FRAME 0x00000001U -#define I2C_FIRST_AND_NEXT_FRAME 0x00000002U -#define I2C_NEXT_FRAME 0x00000004U -#define I2C_FIRST_AND_LAST_FRAME 0x00000008U -#define I2C_LAST_FRAME_NO_STOP 0x00000010U -#define I2C_LAST_FRAME 0x00000020U - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define I2C_OTHER_FRAME (0x00AA0000U) -#define I2C_OTHER_AND_LAST_FRAME (0xAA000000U) -/** - * @} - */ - -/** @defgroup I2C_Interrupt_configuration_definition I2C Interrupt configuration definition - * @brief I2C Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define I2C_IT_BUF I2C_CR2_ITBUFEN -#define I2C_IT_EVT I2C_CR2_ITEVTEN -#define I2C_IT_ERR I2C_CR2_ITERREN -/** - * @} - */ - -/** @defgroup I2C_Flag_definition I2C Flag definition - * @{ - */ - -#define I2C_FLAG_OVR 0x00010800U -#define I2C_FLAG_AF 0x00010400U -#define I2C_FLAG_ARLO 0x00010200U -#define I2C_FLAG_BERR 0x00010100U -#define I2C_FLAG_TXE 0x00010080U -#define I2C_FLAG_RXNE 0x00010040U -#define I2C_FLAG_STOPF 0x00010010U -#define I2C_FLAG_ADD10 0x00010008U -#define I2C_FLAG_BTF 0x00010004U -#define I2C_FLAG_ADDR 0x00010002U -#define I2C_FLAG_SB 0x00010001U -#define I2C_FLAG_DUALF 0x00100080U -#define I2C_FLAG_GENCALL 0x00100010U -#define I2C_FLAG_TRA 0x00100004U -#define I2C_FLAG_BUSY 0x00100002U -#define I2C_FLAG_MSL 0x00100001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @brief Reset I2C handle state. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_I2C_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET) -#endif - -/** @brief Enable or disable the specified I2C interrupts. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__)) -#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Checks if the specified I2C interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the I2C interrupt source to check. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2C flag is set or not. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag - * @arg I2C_FLAG_BERR: Bus error flag - * @arg I2C_FLAG_TXE: Data register empty flag - * @arg I2C_FLAG_RXNE: Data register not empty flag - * @arg I2C_FLAG_STOPF: Stop detection flag - * @arg I2C_FLAG_ADD10: 10-bit header sent flag - * @arg I2C_FLAG_BTF: Byte transfer finished flag - * @arg I2C_FLAG_ADDR: Address sent flag - * Address matched flag - * @arg I2C_FLAG_SB: Start bit flag - * @arg I2C_FLAG_DUALF: Dual flag - * @arg I2C_FLAG_GENCALL: General call header flag - * @arg I2C_FLAG_TRA: Transmitter/Receiver flag - * @arg I2C_FLAG_BUSY: Bus busy flag - * @arg I2C_FLAG_MSL: Master/Slave flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U) ? \ - (((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) : \ - (((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET)) - -/** @brief Clears the I2C pending flags which are cleared by writing 0 in a specific bit. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_FLAG_BERR: Bus error flag - * @retval None - */ -#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & I2C_FLAG_MASK)) - -/** @brief Clears the I2C ADDR pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * This parameter can be I2C where x: 1, 2, or 3 to select the I2C peripheral. - * @retval None - */ -#define __HAL_I2C_CLEAR_ADDRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - tmpreg = (__HANDLE__)->Instance->SR2; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Clears the I2C STOPF pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_CLEAR_STOPFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE); \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Enable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** @brief Disable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** - * @} - */ - -/* Include I2C HAL Extension module */ -#include "stm32f4xx_hal_i2c_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2C_Exported_Functions - * @{ - */ - -/** @addtogroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions******************************/ -HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* IO operation functions ****************************************************/ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); - -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress); - -/******* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -/** - * @} - */ - -/** @addtogroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c); -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ -/* Peripheral State, Mode and Error functions *********************************/ -HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c); -HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c); -uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Constants I2C Private Constants - * @{ - */ -#define I2C_FLAG_MASK 0x0000FFFFU -#define I2C_MIN_PCLK_FREQ_STANDARD 2000000U /*!< 2 MHz */ -#define I2C_MIN_PCLK_FREQ_FAST 4000000U /*!< 4 MHz */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2C_Private_Macros I2C Private Macros - * @{ - */ - -#define I2C_MIN_PCLK_FREQ(__PCLK__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__PCLK__) < I2C_MIN_PCLK_FREQ_STANDARD) : ((__PCLK__) < I2C_MIN_PCLK_FREQ_FAST)) -#define I2C_CCR_CALCULATION(__PCLK__, __SPEED__, __COEFF__) (((((__PCLK__) - 1U)/((__SPEED__) * (__COEFF__))) + 1U) & I2C_CCR_CCR) -#define I2C_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) -#define I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) -#define I2C_SPEED_STANDARD(__PCLK__, __SPEED__) ((I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U) < 4U)? 4U:I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U)) -#define I2C_SPEED_FAST(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__DUTYCYCLE__) == I2C_DUTYCYCLE_2)? I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 3U) : (I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 25U) | I2C_DUTYCYCLE_16_9)) -#define I2C_SPEED(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__SPEED__) <= 100000U)? (I2C_SPEED_STANDARD((__PCLK__), (__SPEED__))) : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__)) & I2C_CCR_CCR) == 0U)? 1U : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__))) | I2C_CCR_FS)) - -#define I2C_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (uint8_t)(~I2C_OAR1_ADD0))) -#define I2C_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) - -#define I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) -#define I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) -#define I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) - -#define I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0xFF00)) >> 8))) -#define I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) - -/** @defgroup I2C_IS_RTC_Definitions I2C Private macros to check input parameters - * @{ - */ -#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DUTYCYCLE_2) || \ - ((CYCLE) == I2C_DUTYCYCLE_16_9)) -#define IS_I2C_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == I2C_ADDRESSINGMODE_7BIT) || \ - ((ADDRESS) == I2C_ADDRESSINGMODE_10BIT)) -#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == I2C_DUALADDRESS_ENABLE)) -#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLE) || \ - ((CALL) == I2C_GENERALCALL_ENABLE)) -#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLE) || \ - ((STRETCH) == I2C_NOSTRETCH_ENABLE)) -#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \ - ((SIZE) == I2C_MEMADD_SIZE_16BIT)) -#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 400000U)) -#define IS_I2C_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) -#define IS_I2C_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) -#define IS_I2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_FIRST_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_NEXT_FRAME) || \ - ((REQUEST) == I2C_NEXT_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME_NO_STOP) || \ - IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) - -#define IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_OTHER_FRAME) || \ - ((REQUEST) == I2C_OTHER_AND_LAST_FRAME)) - -#define I2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) -#define I2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Functions I2C Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_I2C_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c.h + * @author MCD Application Team + * @brief Header file of I2C HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_I2C_H +#define __STM32F4xx_HAL_I2C_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup I2C_Exported_Types I2C Exported Types + * @{ + */ + +/** @defgroup I2C_Configuration_Structure_definition I2C Configuration Structure definition + * @brief I2C Configuration Structure definition + * @{ + */ +typedef struct +{ + uint32_t ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz */ + + uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ + + uint32_t OwnAddress1; /*!< Specifies the first device own address. + This parameter can be a 7-bit or 10-bit address. */ + + uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. + This parameter can be a value of @ref I2C_addressing_mode */ + + uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. + This parameter can be a value of @ref I2C_dual_addressing_mode */ + + uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected + This parameter can be a 7-bit address. */ + + uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. + This parameter can be a value of @ref I2C_general_call_addressing_mode */ + + uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. + This parameter can be a value of @ref I2C_nostretch_mode */ + +} I2C_InitTypeDef; + +/** + * @} + */ + +/** @defgroup HAL_state_structure_definition HAL state structure definition + * @brief HAL State structure definition + * @note HAL I2C State value coding follow below described bitmap : + * b7-b6 Error information + * 00 : No Error + * 01 : Abort (Abort user request on going) + * 10 : Timeout + * 11 : Error + * b5 Peripheral initialization status + * 0 : Reset (Peripheral not initialized) + * 1 : Init done (Peripheral initialized and ready to use. HAL I2C Init function called) + * b4 (not used) + * x : Should be set to 0 + * b3 + * 0 : Ready or Busy (No Listen mode ongoing) + * 1 : Listen (Peripheral in Address Listen Mode) + * b2 Intrinsic process state + * 0 : Ready + * 1 : Busy (Peripheral busy with some configuration or internal operations) + * b1 Rx state + * 0 : Ready (no Rx operation ongoing) + * 1 : Busy (Rx operation ongoing) + * b0 Tx state + * 0 : Ready (no Tx operation ongoing) + * 1 : Busy (Tx operation ongoing) + * @{ + */ +typedef enum +{ + HAL_I2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ + HAL_I2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ + HAL_I2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ + HAL_I2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ + HAL_I2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ + HAL_I2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ + HAL_I2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission + process is ongoing */ + HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception + process is ongoing */ + HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ + HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ + HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */ + +} HAL_I2C_StateTypeDef; + +/** + * @} + */ + +/** @defgroup HAL_mode_structure_definition HAL mode structure definition + * @brief HAL Mode structure definition + * @note HAL I2C Mode value coding follow below described bitmap :\n + * b7 (not used)\n + * x : Should be set to 0\n + * b6\n + * 0 : None\n + * 1 : Memory (HAL I2C communication is in Memory Mode)\n + * b5\n + * 0 : None\n + * 1 : Slave (HAL I2C communication is in Slave Mode)\n + * b4\n + * 0 : None\n + * 1 : Master (HAL I2C communication is in Master Mode)\n + * b3-b2-b1-b0 (not used)\n + * xxxx : Should be set to 0000 + * @{ + */ +typedef enum +{ + HAL_I2C_MODE_NONE = 0x00U, /*!< No I2C communication on going */ + HAL_I2C_MODE_MASTER = 0x10U, /*!< I2C communication is in Master Mode */ + HAL_I2C_MODE_SLAVE = 0x20U, /*!< I2C communication is in Slave Mode */ + HAL_I2C_MODE_MEM = 0x40U /*!< I2C communication is in Memory Mode */ + +} HAL_I2C_ModeTypeDef; + +/** + * @} + */ + +/** @defgroup I2C_Error_Code_definition I2C Error Code definition + * @brief I2C Error Code definition + * @{ + */ +#define HAL_I2C_ERROR_NONE 0x00000000U /*!< No error */ +#define HAL_I2C_ERROR_BERR 0x00000001U /*!< BERR error */ +#define HAL_I2C_ERROR_ARLO 0x00000002U /*!< ARLO error */ +#define HAL_I2C_ERROR_AF 0x00000004U /*!< AF error */ +#define HAL_I2C_ERROR_OVR 0x00000008U /*!< OVR error */ +#define HAL_I2C_ERROR_DMA 0x00000010U /*!< DMA transfer error */ +#define HAL_I2C_ERROR_TIMEOUT 0x00000020U /*!< Timeout Error */ +#define HAL_I2C_ERROR_SIZE 0x00000040U /*!< Size Management error */ +#define HAL_I2C_ERROR_DMA_PARAM 0x00000080U /*!< DMA Parameter Error */ +#define HAL_I2C_WRONG_START 0x00000200U /*!< Wrong start Error */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +#define HAL_I2C_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid Callback error */ +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup I2C_handle_Structure_definition I2C handle Structure definition + * @brief I2C handle Structure definition + * @{ + */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +typedef struct __I2C_HandleTypeDef +#else +typedef struct +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ +{ + I2C_TypeDef *Instance; /*!< I2C registers base address */ + + I2C_InitTypeDef Init; /*!< I2C communication parameters */ + + uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */ + + uint16_t XferSize; /*!< I2C transfer size */ + + __IO uint16_t XferCount; /*!< I2C transfer counter */ + + __IO uint32_t XferOptions; /*!< I2C transfer options */ + + __IO uint32_t PreviousState; /*!< I2C communication Previous state and mode + context for internal usage */ + + DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */ + + DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */ + + HAL_LockTypeDef Lock; /*!< I2C locking object */ + + __IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */ + + __IO HAL_I2C_ModeTypeDef Mode; /*!< I2C communication mode */ + + __IO uint32_t ErrorCode; /*!< I2C Error code */ + + __IO uint32_t Devaddress; /*!< I2C Target device address */ + + __IO uint32_t Memaddress; /*!< I2C Target memory address */ + + __IO uint32_t MemaddSize; /*!< I2C Target memory address size */ + + __IO uint32_t EventCount; /*!< I2C Event counter */ + + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + void (* MasterTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Tx Transfer completed callback */ + void (* MasterRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Rx Transfer completed callback */ + void (* SlaveTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Tx Transfer completed callback */ + void (* SlaveRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Rx Transfer completed callback */ + void (* ListenCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Listen Complete callback */ + void (* MemTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Tx Transfer completed callback */ + void (* MemRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Rx Transfer completed callback */ + void (* ErrorCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Error callback */ + void (* AbortCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Abort callback */ + + void (* AddrCallback)(struct __I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< I2C Slave Address Match callback */ + + void (* MspInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp Init callback */ + void (* MspDeInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp DeInit callback */ + +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ +} I2C_HandleTypeDef; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +/** + * @brief HAL I2C Callback ID enumeration definition + */ +typedef enum +{ + HAL_I2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< I2C Master Tx Transfer completed callback ID */ + HAL_I2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< I2C Master Rx Transfer completed callback ID */ + HAL_I2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< I2C Slave Tx Transfer completed callback ID */ + HAL_I2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< I2C Slave Rx Transfer completed callback ID */ + HAL_I2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< I2C Listen Complete callback ID */ + HAL_I2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< I2C Memory Tx Transfer callback ID */ + HAL_I2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< I2C Memory Rx Transfer completed callback ID */ + HAL_I2C_ERROR_CB_ID = 0x07U, /*!< I2C Error callback ID */ + HAL_I2C_ABORT_CB_ID = 0x08U, /*!< I2C Abort callback ID */ + + HAL_I2C_MSPINIT_CB_ID = 0x09U, /*!< I2C Msp Init callback ID */ + HAL_I2C_MSPDEINIT_CB_ID = 0x0AU /*!< I2C Msp DeInit callback ID */ + +} HAL_I2C_CallbackIDTypeDef; + +/** + * @brief HAL I2C Callback pointer definition + */ +typedef void (*pI2C_CallbackTypeDef)(I2C_HandleTypeDef *hi2c); /*!< pointer to an I2C callback function */ +typedef void (*pI2C_AddrCallbackTypeDef)(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ + +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** + * @} + */ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup I2C_Exported_Constants I2C Exported Constants + * @{ + */ + +/** @defgroup I2C_duty_cycle_in_fast_mode I2C duty cycle in fast mode + * @{ + */ +#define I2C_DUTYCYCLE_2 0x00000000U +#define I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY +/** + * @} + */ + +/** @defgroup I2C_addressing_mode I2C addressing mode + * @{ + */ +#define I2C_ADDRESSINGMODE_7BIT 0x00004000U +#define I2C_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) +/** + * @} + */ + +/** @defgroup I2C_dual_addressing_mode I2C dual addressing mode + * @{ + */ +#define I2C_DUALADDRESS_DISABLE 0x00000000U +#define I2C_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL +/** + * @} + */ + +/** @defgroup I2C_general_call_addressing_mode I2C general call addressing mode + * @{ + */ +#define I2C_GENERALCALL_DISABLE 0x00000000U +#define I2C_GENERALCALL_ENABLE I2C_CR1_ENGC +/** + * @} + */ + +/** @defgroup I2C_nostretch_mode I2C nostretch mode + * @{ + */ +#define I2C_NOSTRETCH_DISABLE 0x00000000U +#define I2C_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH +/** + * @} + */ + +/** @defgroup I2C_Memory_Address_Size I2C Memory Address Size + * @{ + */ +#define I2C_MEMADD_SIZE_8BIT 0x00000001U +#define I2C_MEMADD_SIZE_16BIT 0x00000010U +/** + * @} + */ + +/** @defgroup I2C_XferDirection_definition I2C XferDirection definition + * @{ + */ +#define I2C_DIRECTION_RECEIVE 0x00000000U +#define I2C_DIRECTION_TRANSMIT 0x00000001U +/** + * @} + */ + +/** @defgroup I2C_XferOptions_definition I2C XferOptions definition + * @{ + */ +#define I2C_FIRST_FRAME 0x00000001U +#define I2C_FIRST_AND_NEXT_FRAME 0x00000002U +#define I2C_NEXT_FRAME 0x00000004U +#define I2C_FIRST_AND_LAST_FRAME 0x00000008U +#define I2C_LAST_FRAME_NO_STOP 0x00000010U +#define I2C_LAST_FRAME 0x00000020U + +/* List of XferOptions in usage of : + * 1- Restart condition in all use cases (direction change or not) + */ +#define I2C_OTHER_FRAME (0x00AA0000U) +#define I2C_OTHER_AND_LAST_FRAME (0xAA000000U) +/** + * @} + */ + +/** @defgroup I2C_Interrupt_configuration_definition I2C Interrupt configuration definition + * @brief I2C Interrupt definition + * Elements values convention: 0xXXXXXXXX + * - XXXXXXXX : Interrupt control mask + * @{ + */ +#define I2C_IT_BUF I2C_CR2_ITBUFEN +#define I2C_IT_EVT I2C_CR2_ITEVTEN +#define I2C_IT_ERR I2C_CR2_ITERREN +/** + * @} + */ + +/** @defgroup I2C_Flag_definition I2C Flag definition + * @{ + */ + +#define I2C_FLAG_OVR 0x00010800U +#define I2C_FLAG_AF 0x00010400U +#define I2C_FLAG_ARLO 0x00010200U +#define I2C_FLAG_BERR 0x00010100U +#define I2C_FLAG_TXE 0x00010080U +#define I2C_FLAG_RXNE 0x00010040U +#define I2C_FLAG_STOPF 0x00010010U +#define I2C_FLAG_ADD10 0x00010008U +#define I2C_FLAG_BTF 0x00010004U +#define I2C_FLAG_ADDR 0x00010002U +#define I2C_FLAG_SB 0x00010001U +#define I2C_FLAG_DUALF 0x00100080U +#define I2C_FLAG_GENCALL 0x00100010U +#define I2C_FLAG_TRA 0x00100004U +#define I2C_FLAG_BUSY 0x00100002U +#define I2C_FLAG_MSL 0x00100001U +/** + * @} + */ + +/** + * @} + */ + +/* Exported macros -----------------------------------------------------------*/ + +/** @defgroup I2C_Exported_Macros I2C Exported Macros + * @{ + */ + +/** @brief Reset I2C handle state. + * @param __HANDLE__ specifies the I2C Handle. + * @retval None + */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ + (__HANDLE__)->State = HAL_I2C_STATE_RESET; \ + (__HANDLE__)->MspInitCallback = NULL; \ + (__HANDLE__)->MspDeInitCallback = NULL; \ + } while(0) +#else +#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET) +#endif + +/** @brief Enable or disable the specified I2C interrupts. + * @param __HANDLE__ specifies the I2C Handle. + * @param __INTERRUPT__ specifies the interrupt source to enable or disable. + * This parameter can be one of the following values: + * @arg I2C_IT_BUF: Buffer interrupt enable + * @arg I2C_IT_EVT: Event interrupt enable + * @arg I2C_IT_ERR: Error interrupt enable + * @retval None + */ +#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__)) +#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) + +/** @brief Checks if the specified I2C interrupt source is enabled or disabled. + * @param __HANDLE__ specifies the I2C Handle. + * @param __INTERRUPT__ specifies the I2C interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_BUF: Buffer interrupt enable + * @arg I2C_IT_EVT: Event interrupt enable + * @arg I2C_IT_ERR: Error interrupt enable + * @retval The new state of __INTERRUPT__ (TRUE or FALSE). + */ +#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) + +/** @brief Checks whether the specified I2C flag is set or not. + * @param __HANDLE__ specifies the I2C Handle. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_OVR: Overrun/Underrun flag + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag + * @arg I2C_FLAG_BERR: Bus error flag + * @arg I2C_FLAG_TXE: Data register empty flag + * @arg I2C_FLAG_RXNE: Data register not empty flag + * @arg I2C_FLAG_STOPF: Stop detection flag + * @arg I2C_FLAG_ADD10: 10-bit header sent flag + * @arg I2C_FLAG_BTF: Byte transfer finished flag + * @arg I2C_FLAG_ADDR: Address sent flag + * Address matched flag + * @arg I2C_FLAG_SB: Start bit flag + * @arg I2C_FLAG_DUALF: Dual flag + * @arg I2C_FLAG_GENCALL: General call header flag + * @arg I2C_FLAG_TRA: Transmitter/Receiver flag + * @arg I2C_FLAG_BUSY: Bus busy flag + * @arg I2C_FLAG_MSL: Master/Slave flag + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U) ? \ + (((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) : \ + (((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET)) + +/** @brief Clears the I2C pending flags which are cleared by writing 0 in a specific bit. + * @param __HANDLE__ specifies the I2C Handle. + * @param __FLAG__ specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * @retval None + */ +#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & I2C_FLAG_MASK)) + +/** @brief Clears the I2C ADDR pending flag. + * @param __HANDLE__ specifies the I2C Handle. + * This parameter can be I2C where x: 1, 2, or 3 to select the I2C peripheral. + * @retval None + */ +#define __HAL_I2C_CLEAR_ADDRFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg = 0x00U; \ + tmpreg = (__HANDLE__)->Instance->SR1; \ + tmpreg = (__HANDLE__)->Instance->SR2; \ + UNUSED(tmpreg); \ + } while(0) + +/** @brief Clears the I2C STOPF pending flag. + * @param __HANDLE__ specifies the I2C Handle. + * @retval None + */ +#define __HAL_I2C_CLEAR_STOPFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg = 0x00U; \ + tmpreg = (__HANDLE__)->Instance->SR1; \ + SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE); \ + UNUSED(tmpreg); \ + } while(0) + +/** @brief Enable the specified I2C peripheral. + * @param __HANDLE__ specifies the I2C Handle. + * @retval None + */ +#define __HAL_I2C_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) + +/** @brief Disable the specified I2C peripheral. + * @param __HANDLE__ specifies the I2C Handle. + * @retval None + */ +#define __HAL_I2C_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) + +/** + * @} + */ + +/* Include I2C HAL Extension module */ +#include "stm32f4xx_hal_i2c_ex.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup I2C_Exported_Functions + * @{ + */ + +/** @addtogroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions + * @{ + */ +/* Initialization and de-initialization functions******************************/ +HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c); +HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c); + +/* Callbacks Register/UnRegister functions ***********************************/ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID); + +HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @addtogroup I2C_Exported_Functions_Group2 Input and Output operation functions + * @{ + */ +/* IO operation functions ****************************************************/ +/******* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); + +/******* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); + +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c); +HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c); +HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress); + +/******* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); + +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); +/** + * @} + */ + +/** @addtogroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks + * @{ + */ +/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ +void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c); +void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); +void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c); +void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c); +/** + * @} + */ + +/** @addtogroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions + * @{ + */ +/* Peripheral State, Mode and Error functions *********************************/ +HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c); +HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c); +uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c); + +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup I2C_Private_Constants I2C Private Constants + * @{ + */ +#define I2C_FLAG_MASK 0x0000FFFFU +#define I2C_MIN_PCLK_FREQ_STANDARD 2000000U /*!< 2 MHz */ +#define I2C_MIN_PCLK_FREQ_FAST 4000000U /*!< 4 MHz */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup I2C_Private_Macros I2C Private Macros + * @{ + */ + +#define I2C_MIN_PCLK_FREQ(__PCLK__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__PCLK__) < I2C_MIN_PCLK_FREQ_STANDARD) : ((__PCLK__) < I2C_MIN_PCLK_FREQ_FAST)) +#define I2C_CCR_CALCULATION(__PCLK__, __SPEED__, __COEFF__) (((((__PCLK__) - 1U)/((__SPEED__) * (__COEFF__))) + 1U) & I2C_CCR_CCR) +#define I2C_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) +#define I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) +#define I2C_SPEED_STANDARD(__PCLK__, __SPEED__) ((I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U) < 4U)? 4U:I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U)) +#define I2C_SPEED_FAST(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__DUTYCYCLE__) == I2C_DUTYCYCLE_2)? I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 3U) : (I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 25U) | I2C_DUTYCYCLE_16_9)) +#define I2C_SPEED(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__SPEED__) <= 100000U)? (I2C_SPEED_STANDARD((__PCLK__), (__SPEED__))) : \ + ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__)) & I2C_CCR_CCR) == 0U)? 1U : \ + ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__))) | I2C_CCR_FS)) + +#define I2C_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (uint8_t)(~I2C_OAR1_ADD0))) +#define I2C_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) + +#define I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) +#define I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) +#define I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) + +#define I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0xFF00)) >> 8))) +#define I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) + +/** @defgroup I2C_IS_RTC_Definitions I2C Private macros to check input parameters + * @{ + */ +#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DUTYCYCLE_2) || \ + ((CYCLE) == I2C_DUTYCYCLE_16_9)) +#define IS_I2C_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == I2C_ADDRESSINGMODE_7BIT) || \ + ((ADDRESS) == I2C_ADDRESSINGMODE_10BIT)) +#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLE) || \ + ((ADDRESS) == I2C_DUALADDRESS_ENABLE)) +#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLE) || \ + ((CALL) == I2C_GENERALCALL_ENABLE)) +#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLE) || \ + ((STRETCH) == I2C_NOSTRETCH_ENABLE)) +#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \ + ((SIZE) == I2C_MEMADD_SIZE_16BIT)) +#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 400000U)) +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) +#define IS_I2C_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) +#define IS_I2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_FIRST_FRAME) || \ + ((REQUEST) == I2C_FIRST_AND_NEXT_FRAME) || \ + ((REQUEST) == I2C_NEXT_FRAME) || \ + ((REQUEST) == I2C_FIRST_AND_LAST_FRAME) || \ + ((REQUEST) == I2C_LAST_FRAME) || \ + ((REQUEST) == I2C_LAST_FRAME_NO_STOP) || \ + IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) + +#define IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_OTHER_FRAME) || \ + ((REQUEST) == I2C_OTHER_AND_LAST_FRAME)) + +#define I2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) +#define I2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup I2C_Private_Functions I2C Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + + +#endif /* __STM32F4xx_HAL_I2C_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h index 31ad99c..e2ee7c8 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c_ex.h - * @author MCD Application Team - * @brief Header file of I2C HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_EX_H -#define __STM32F4xx_HAL_I2C_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2CEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2CEx_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2CEx_Analog_Filter I2C Analog Filter - * @{ - */ -#define I2C_ANALOGFILTER_ENABLE 0x00000000U -#define I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2CEx_Exported_Functions - * @{ - */ - -/** @addtogroup I2CEx_Exported_Functions_Group1 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Constants I2C Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Macros I2C Private Macros - * @{ - */ -#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLE) || \ - ((FILTER) == I2C_ANALOGFILTER_DISABLE)) -#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_I2C_EX_H */ - - +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c_ex.h + * @author MCD Application Team + * @brief Header file of I2C HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_I2C_EX_H +#define __STM32F4xx_HAL_I2C_EX_H + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup I2CEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup I2CEx_Exported_Constants I2C Exported Constants + * @{ + */ + +/** @defgroup I2CEx_Analog_Filter I2C Analog Filter + * @{ + */ +#define I2C_ANALOGFILTER_ENABLE 0x00000000U +#define I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup I2CEx_Exported_Functions + * @{ + */ + +/** @addtogroup I2CEx_Exported_Functions_Group1 + * @{ + */ +/* Peripheral Control functions ************************************************/ +HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter); +HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter); +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup I2CEx_Private_Constants I2C Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup I2CEx_Private_Macros I2C Private Macros + * @{ + */ +#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLE) || \ + ((FILTER) == I2C_ANALOGFILTER_DISABLE)) +#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_I2C_EX_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h new file mode 100644 index 0000000..6e3c160 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h @@ -0,0 +1,220 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_iwdg.h + * @author MCD Application Team + * @brief Header file of IWDG HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_IWDG_H +#define STM32F4xx_HAL_IWDG_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup IWDG IWDG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup IWDG_Exported_Types IWDG Exported Types + * @{ + */ + +/** + * @brief IWDG Init structure definition + */ +typedef struct +{ + uint32_t Prescaler; /*!< Select the prescaler of the IWDG. + This parameter can be a value of @ref IWDG_Prescaler */ + + uint32_t Reload; /*!< Specifies the IWDG down-counter reload value. + This parameter must be a number between Min_Data = 0 and Max_Data = 0x0FFF */ + +} IWDG_InitTypeDef; + +/** + * @brief IWDG Handle Structure definition + */ +typedef struct +{ + IWDG_TypeDef *Instance; /*!< Register base address */ + + IWDG_InitTypeDef Init; /*!< IWDG required parameters */ +} IWDG_HandleTypeDef; + + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup IWDG_Exported_Constants IWDG Exported Constants + * @{ + */ + +/** @defgroup IWDG_Prescaler IWDG Prescaler + * @{ + */ +#define IWDG_PRESCALER_4 0x00000000u /*!< IWDG prescaler set to 4 */ +#define IWDG_PRESCALER_8 IWDG_PR_PR_0 /*!< IWDG prescaler set to 8 */ +#define IWDG_PRESCALER_16 IWDG_PR_PR_1 /*!< IWDG prescaler set to 16 */ +#define IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 32 */ +#define IWDG_PRESCALER_64 IWDG_PR_PR_2 /*!< IWDG prescaler set to 64 */ +#define IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 128 */ +#define IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< IWDG prescaler set to 256 */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macros -----------------------------------------------------------*/ +/** @defgroup IWDG_Exported_Macros IWDG Exported Macros + * @{ + */ + +/** + * @brief Enable the IWDG peripheral. + * @param __HANDLE__ IWDG handle + * @retval None + */ +#define __HAL_IWDG_START(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_ENABLE) + +/** + * @brief Reload IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param __HANDLE__ IWDG handle + * @retval None + */ +#define __HAL_IWDG_RELOAD_COUNTER(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_RELOAD) + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup IWDG_Exported_Functions IWDG Exported Functions + * @{ + */ + +/** @defgroup IWDG_Exported_Functions_Group1 Initialization and Start functions + * @{ + */ +/* Initialization/Start functions ********************************************/ +HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg); +/** + * @} + */ + +/** @defgroup IWDG_Exported_Functions_Group2 IO operation functions + * @{ + */ +/* I/O operation functions ****************************************************/ +HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg); +/** + * @} + */ + +/** + * @} + */ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup IWDG_Private_Constants IWDG Private Constants + * @{ + */ + +/** + * @brief IWDG Key Register BitMask + */ +#define IWDG_KEY_RELOAD 0x0000AAAAu /*!< IWDG Reload Counter Enable */ +#define IWDG_KEY_ENABLE 0x0000CCCCu /*!< IWDG Peripheral Enable */ +#define IWDG_KEY_WRITE_ACCESS_ENABLE 0x00005555u /*!< IWDG KR Write Access Enable */ +#define IWDG_KEY_WRITE_ACCESS_DISABLE 0x00000000u /*!< IWDG KR Write Access Disable */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup IWDG_Private_Macros IWDG Private Macros + * @{ + */ + +/** + * @brief Enable write access to IWDG_PR and IWDG_RLR registers. + * @param __HANDLE__ IWDG handle + * @retval None + */ +#define IWDG_ENABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_ENABLE) + +/** + * @brief Disable write access to IWDG_PR and IWDG_RLR registers. + * @param __HANDLE__ IWDG handle + * @retval None + */ +#define IWDG_DISABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_DISABLE) + +/** + * @brief Check IWDG prescaler value. + * @param __PRESCALER__ IWDG prescaler value + * @retval None + */ +#define IS_IWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == IWDG_PRESCALER_4) || \ + ((__PRESCALER__) == IWDG_PRESCALER_8) || \ + ((__PRESCALER__) == IWDG_PRESCALER_16) || \ + ((__PRESCALER__) == IWDG_PRESCALER_32) || \ + ((__PRESCALER__) == IWDG_PRESCALER_64) || \ + ((__PRESCALER__) == IWDG_PRESCALER_128)|| \ + ((__PRESCALER__) == IWDG_PRESCALER_256)) + +/** + * @brief Check IWDG reload value. + * @param __RELOAD__ IWDG reload value + * @retval None + */ +#define IS_IWDG_RELOAD(__RELOAD__) ((__RELOAD__) <= IWDG_RLR_RL) + + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_HAL_IWDG_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h index 92488b2..a9f0c5b 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h @@ -1,459 +1,459 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd.h - * @author MCD Application Team - * @brief Header file of PCD HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_H -#define STM32F4xx_HAL_PCD_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usb.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup PCD_Exported_Types PCD Exported Types - * @{ - */ - -/** - * @brief PCD State structure definition - */ -typedef enum -{ - HAL_PCD_STATE_RESET = 0x00, - HAL_PCD_STATE_READY = 0x01, - HAL_PCD_STATE_ERROR = 0x02, - HAL_PCD_STATE_BUSY = 0x03, - HAL_PCD_STATE_TIMEOUT = 0x04 -} PCD_StateTypeDef; - -/* Device LPM suspend state */ -typedef enum -{ - LPM_L0 = 0x00, /* on */ - LPM_L1 = 0x01, /* LPM L1 sleep */ - LPM_L2 = 0x02, /* suspend */ - LPM_L3 = 0x03, /* off */ -} PCD_LPM_StateTypeDef; - -typedef enum -{ - PCD_LPM_L0_ACTIVE = 0x00, /* on */ - PCD_LPM_L1_ACTIVE = 0x01, /* LPM L1 sleep */ -} PCD_LPM_MsgTypeDef; - -typedef enum -{ - PCD_BCD_ERROR = 0xFF, - PCD_BCD_CONTACT_DETECTION = 0xFE, - PCD_BCD_STD_DOWNSTREAM_PORT = 0xFD, - PCD_BCD_CHARGING_DOWNSTREAM_PORT = 0xFC, - PCD_BCD_DEDICATED_CHARGING_PORT = 0xFB, - PCD_BCD_DISCOVERY_COMPLETED = 0x00, - -} PCD_BCD_MsgTypeDef; - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -typedef USB_OTG_GlobalTypeDef PCD_TypeDef; -typedef USB_OTG_CfgTypeDef PCD_InitTypeDef; -typedef USB_OTG_EPTypeDef PCD_EPTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @brief PCD Handle Structure definition - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -typedef struct __PCD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -{ - PCD_TypeDef *Instance; /*!< Register base address */ - PCD_InitTypeDef Init; /*!< PCD required parameters */ - __IO uint8_t USB_Address; /*!< USB Address */ - PCD_EPTypeDef IN_ep[16]; /*!< IN endpoint parameters */ - PCD_EPTypeDef OUT_ep[16]; /*!< OUT endpoint parameters */ - HAL_LockTypeDef Lock; /*!< PCD peripheral status */ - __IO PCD_StateTypeDef State; /*!< PCD communication state */ - __IO uint32_t ErrorCode; /*!< PCD Error code */ - uint32_t Setup[12]; /*!< Setup packet buffer */ - PCD_LPM_StateTypeDef LPM_State; /*!< LPM State */ - uint32_t BESL; - uint32_t FrameNumber; /*!< Store Current Frame number */ - - - uint32_t lpm_active; /*!< Enable or disable the Link Power Management . - This parameter can be set to ENABLE or DISABLE */ - - uint32_t battery_charging_active; /*!< Enable or disable Battery charging. - This parameter can be set to ENABLE or DISABLE */ - void *pData; /*!< Pointer to upper stack Handler */ - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - void (* SOFCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD SOF callback */ - void (* SetupStageCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Setup Stage callback */ - void (* ResetCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Reset callback */ - void (* SuspendCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Suspend callback */ - void (* ResumeCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Resume callback */ - void (* ConnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Connect callback */ - void (* DisconnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Disconnect callback */ - - void (* DataOutStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data OUT Stage callback */ - void (* DataInStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data IN Stage callback */ - void (* ISOOUTIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO OUT Incomplete callback */ - void (* ISOINIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO IN Incomplete callback */ - void (* BCDCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< USB OTG PCD BCD callback */ - void (* LPMCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< USB OTG PCD LPM callback */ - - void (* MspInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp Init callback */ - void (* MspDeInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp DeInit callback */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -} PCD_HandleTypeDef; - -/** - * @} - */ - -/* Include PCD HAL Extended module */ -#include "stm32f4xx_hal_pcd_ex.h" - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -/** @defgroup PCD_Speed PCD Speed - * @{ - */ -#define PCD_SPEED_HIGH USBD_HS_SPEED -#define PCD_SPEED_HIGH_IN_FULL USBD_HSINFS_SPEED -#define PCD_SPEED_FULL USBD_FS_SPEED -/** - * @} - */ - -/** @defgroup PCD_PHY_Module PCD PHY Module - * @{ - */ -#define PCD_PHY_ULPI 1U -#define PCD_PHY_EMBEDDED 2U -#define PCD_PHY_UTMI 3U -/** - * @} - */ - -/** @defgroup PCD_Error_Code_definition PCD Error Code definition - * @brief PCD Error Code definition - * @{ - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -#define HAL_PCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup PCD_Exported_Macros PCD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define __HAL_PCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) -#define __HAL_PCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) - -#define __HAL_PCD_GET_FLAG(__HANDLE__, __INTERRUPT__) \ - ((USB_ReadInterrupts((__HANDLE__)->Instance) & (__INTERRUPT__)) == (__INTERRUPT__)) - -#define __HAL_PCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) &= (__INTERRUPT__)) -#define __HAL_PCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) - -#define __HAL_PCD_UNGATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) &= ~(USB_OTG_PCGCCTL_STOPCLK) - -#define __HAL_PCD_GATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) |= USB_OTG_PCGCCTL_STOPCLK - -#define __HAL_PCD_IS_PHY_SUSPENDED(__HANDLE__) \ - ((*(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE)) & 0x10U) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (USB_OTG_HS_WAKEUP_EXTI_LINE) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_HS_WAKEUP_EXTI_LINE; \ - } while(0U) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= USB_OTG_FS_WAKEUP_EXTI_LINE -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = USB_OTG_FS_WAKEUP_EXTI_LINE - -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_FS_WAKEUP_EXTI_LINE; \ - } while(0U) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCD_Exported_Functions PCD Exported Functions - * @{ - */ - -/* Initialization/de-initialization functions ********************************/ -/** @addtogroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -/** @defgroup HAL_PCD_Callback_ID_enumeration_definition HAL USB OTG PCD Callback ID enumeration definition - * @brief HAL USB OTG PCD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_PCD_SOF_CB_ID = 0x01, /*!< USB PCD SOF callback ID */ - HAL_PCD_SETUPSTAGE_CB_ID = 0x02, /*!< USB PCD Setup Stage callback ID */ - HAL_PCD_RESET_CB_ID = 0x03, /*!< USB PCD Reset callback ID */ - HAL_PCD_SUSPEND_CB_ID = 0x04, /*!< USB PCD Suspend callback ID */ - HAL_PCD_RESUME_CB_ID = 0x05, /*!< USB PCD Resume callback ID */ - HAL_PCD_CONNECT_CB_ID = 0x06, /*!< USB PCD Connect callback ID */ - HAL_PCD_DISCONNECT_CB_ID = 0x07, /*!< USB PCD Disconnect callback ID */ - - HAL_PCD_MSPINIT_CB_ID = 0x08, /*!< USB PCD MspInit callback ID */ - HAL_PCD_MSPDEINIT_CB_ID = 0x09 /*!< USB PCD MspDeInit callback ID */ - -} HAL_PCD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_PCD_Callback_pointer_definition HAL USB OTG PCD Callback pointer definition - * @brief HAL USB OTG PCD Callback pointer definition - * @{ - */ - -typedef void (*pPCD_CallbackTypeDef)(PCD_HandleTypeDef *hpcd); /*!< pointer to a common USB OTG PCD callback function */ -typedef void (*pPCD_DataOutStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data OUT Stage callback */ -typedef void (*pPCD_DataInStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data IN Stage callback */ -typedef void (*pPCD_IsoOutIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO OUT Incomplete callback */ -typedef void (*pPCD_IsoInIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO IN Incomplete callback */ -typedef void (*pPCD_LpmCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< pointer to USB OTG PCD LPM callback */ -typedef void (*pPCD_BcdCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< pointer to USB OTG PCD BCD callback */ - -/** - * @} - */ - -HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID, - pPCD_CallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataOutStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataInStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoOutIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoInIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions ***************************************************/ -/* Non-Blocking mode: Interrupt */ -/** @addtogroup PCD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd); -void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd); -void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ -/** @addtogroup PCD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address); -HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint16_t ep_mps, uint8_t ep_type); -HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len); -HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len); -HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Abort(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_SetTestMode(PCD_HandleTypeDef *hpcd, uint8_t testmode); - -uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ -/** @addtogroup PCD_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PCD_Private_Constants PCD Private Constants - * @{ - */ -/** @defgroup USB_EXTI_Line_Interrupt USB EXTI line interrupt - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_OTG_FS_WAKEUP_EXTI_LINE (0x1U << 18) /*!< USB FS EXTI Line WakeUp Interrupt */ -#define USB_OTG_HS_WAKEUP_EXTI_LINE (0x1U << 20) /*!< USB HS EXTI Line WakeUp Interrupt */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ -/** - * @} - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#ifndef USB_OTG_DOEPINT_OTEPSPR -#define USB_OTG_DOEPINT_OTEPSPR (0x1UL << 5) /*!< Status Phase Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_OTEPSPR */ - -#ifndef USB_OTG_DOEPMSK_OTEPSPRM -#define USB_OTG_DOEPMSK_OTEPSPRM (0x1UL << 5) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_OTEPSPRM */ - -#ifndef USB_OTG_DOEPINT_NAK -#define USB_OTG_DOEPINT_NAK (0x1UL << 13) /*!< NAK interrupt */ -#endif /* defined USB_OTG_DOEPINT_NAK */ - -#ifndef USB_OTG_DOEPMSK_NAKM -#define USB_OTG_DOEPMSK_NAKM (0x1UL << 13) /*!< OUT Packet NAK interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NAKM */ - -#ifndef USB_OTG_DOEPINT_STPKTRX -#define USB_OTG_DOEPINT_STPKTRX (0x1UL << 15) /*!< Setup Packet Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_STPKTRX */ - -#ifndef USB_OTG_DOEPMSK_NYETM -#define USB_OTG_DOEPMSK_NYETM (0x1UL << 14) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NYETM */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PCD_Private_Macros PCD Private Macros - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_PCD_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd.h + * @author MCD Application Team + * @brief Header file of PCD HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_PCD_H +#define STM32F4xx_HAL_PCD_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_usb.h" + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup PCD + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup PCD_Exported_Types PCD Exported Types + * @{ + */ + +/** + * @brief PCD State structure definition + */ +typedef enum +{ + HAL_PCD_STATE_RESET = 0x00, + HAL_PCD_STATE_READY = 0x01, + HAL_PCD_STATE_ERROR = 0x02, + HAL_PCD_STATE_BUSY = 0x03, + HAL_PCD_STATE_TIMEOUT = 0x04 +} PCD_StateTypeDef; + +/* Device LPM suspend state */ +typedef enum +{ + LPM_L0 = 0x00, /* on */ + LPM_L1 = 0x01, /* LPM L1 sleep */ + LPM_L2 = 0x02, /* suspend */ + LPM_L3 = 0x03, /* off */ +} PCD_LPM_StateTypeDef; + +typedef enum +{ + PCD_LPM_L0_ACTIVE = 0x00, /* on */ + PCD_LPM_L1_ACTIVE = 0x01, /* LPM L1 sleep */ +} PCD_LPM_MsgTypeDef; + +typedef enum +{ + PCD_BCD_ERROR = 0xFF, + PCD_BCD_CONTACT_DETECTION = 0xFE, + PCD_BCD_STD_DOWNSTREAM_PORT = 0xFD, + PCD_BCD_CHARGING_DOWNSTREAM_PORT = 0xFC, + PCD_BCD_DEDICATED_CHARGING_PORT = 0xFB, + PCD_BCD_DISCOVERY_COMPLETED = 0x00, + +} PCD_BCD_MsgTypeDef; + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +typedef USB_OTG_GlobalTypeDef PCD_TypeDef; +typedef USB_OTG_CfgTypeDef PCD_InitTypeDef; +typedef USB_OTG_EPTypeDef PCD_EPTypeDef; +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +/** + * @brief PCD Handle Structure definition + */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) +typedef struct __PCD_HandleTypeDef +#else +typedef struct +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ +{ + PCD_TypeDef *Instance; /*!< Register base address */ + PCD_InitTypeDef Init; /*!< PCD required parameters */ + __IO uint8_t USB_Address; /*!< USB Address */ + PCD_EPTypeDef IN_ep[16]; /*!< IN endpoint parameters */ + PCD_EPTypeDef OUT_ep[16]; /*!< OUT endpoint parameters */ + HAL_LockTypeDef Lock; /*!< PCD peripheral status */ + __IO PCD_StateTypeDef State; /*!< PCD communication state */ + __IO uint32_t ErrorCode; /*!< PCD Error code */ + uint32_t Setup[12]; /*!< Setup packet buffer */ + PCD_LPM_StateTypeDef LPM_State; /*!< LPM State */ + uint32_t BESL; + uint32_t FrameNumber; /*!< Store Current Frame number */ + + + uint32_t lpm_active; /*!< Enable or disable the Link Power Management . + This parameter can be set to ENABLE or DISABLE */ + + uint32_t battery_charging_active; /*!< Enable or disable Battery charging. + This parameter can be set to ENABLE or DISABLE */ + void *pData; /*!< Pointer to upper stack Handler */ + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + void (* SOFCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD SOF callback */ + void (* SetupStageCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Setup Stage callback */ + void (* ResetCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Reset callback */ + void (* SuspendCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Suspend callback */ + void (* ResumeCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Resume callback */ + void (* ConnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Connect callback */ + void (* DisconnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Disconnect callback */ + + void (* DataOutStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data OUT Stage callback */ + void (* DataInStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data IN Stage callback */ + void (* ISOOUTIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO OUT Incomplete callback */ + void (* ISOINIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO IN Incomplete callback */ + void (* BCDCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< USB OTG PCD BCD callback */ + void (* LPMCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< USB OTG PCD LPM callback */ + + void (* MspInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp Init callback */ + void (* MspDeInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp DeInit callback */ +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ +} PCD_HandleTypeDef; + +/** + * @} + */ + +/* Include PCD HAL Extended module */ +#include "stm32f4xx_hal_pcd_ex.h" + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup PCD_Exported_Constants PCD Exported Constants + * @{ + */ + +/** @defgroup PCD_Speed PCD Speed + * @{ + */ +#define PCD_SPEED_HIGH USBD_HS_SPEED +#define PCD_SPEED_HIGH_IN_FULL USBD_HSINFS_SPEED +#define PCD_SPEED_FULL USBD_FS_SPEED +/** + * @} + */ + +/** @defgroup PCD_PHY_Module PCD PHY Module + * @{ + */ +#define PCD_PHY_ULPI 1U +#define PCD_PHY_EMBEDDED 2U +#define PCD_PHY_UTMI 3U +/** + * @} + */ + +/** @defgroup PCD_Error_Code_definition PCD Error Code definition + * @brief PCD Error Code definition + * @{ + */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) +#define HAL_PCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macros -----------------------------------------------------------*/ +/** @defgroup PCD_Exported_Macros PCD Exported Macros + * @brief macros to handle interrupts and specific clock configurations + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +#define __HAL_PCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) +#define __HAL_PCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) + +#define __HAL_PCD_GET_FLAG(__HANDLE__, __INTERRUPT__) \ + ((USB_ReadInterrupts((__HANDLE__)->Instance) & (__INTERRUPT__)) == (__INTERRUPT__)) + +#define __HAL_PCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) &= (__INTERRUPT__)) +#define __HAL_PCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) + +#define __HAL_PCD_UNGATE_PHYCLOCK(__HANDLE__) \ + *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) &= ~(USB_OTG_PCGCCTL_STOPCLK) + +#define __HAL_PCD_GATE_PHYCLOCK(__HANDLE__) \ + *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) |= USB_OTG_PCGCCTL_STOPCLK + +#define __HAL_PCD_IS_PHY_SUSPENDED(__HANDLE__) \ + ((*(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE)) & 0x10U) + +#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (USB_OTG_HS_WAKEUP_EXTI_LINE) +#define __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE) +#define __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_HS_WAKEUP_EXTI_LINE) +#define __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (USB_OTG_HS_WAKEUP_EXTI_LINE) + +#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ + do { \ + EXTI->FTSR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE); \ + EXTI->RTSR |= USB_OTG_HS_WAKEUP_EXTI_LINE; \ + } while(0U) +#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= USB_OTG_FS_WAKEUP_EXTI_LINE +#define __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE) +#define __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_FS_WAKEUP_EXTI_LINE) +#define __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = USB_OTG_FS_WAKEUP_EXTI_LINE + +#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ + do { \ + EXTI->FTSR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE); \ + EXTI->RTSR |= USB_OTG_FS_WAKEUP_EXTI_LINE; \ + } while(0U) +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup PCD_Exported_Functions PCD Exported Functions + * @{ + */ + +/* Initialization/de-initialization functions ********************************/ +/** @addtogroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions + * @{ + */ +HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd); +void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd); +void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd); + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) +/** @defgroup HAL_PCD_Callback_ID_enumeration_definition HAL USB OTG PCD Callback ID enumeration definition + * @brief HAL USB OTG PCD Callback ID enumeration definition + * @{ + */ +typedef enum +{ + HAL_PCD_SOF_CB_ID = 0x01, /*!< USB PCD SOF callback ID */ + HAL_PCD_SETUPSTAGE_CB_ID = 0x02, /*!< USB PCD Setup Stage callback ID */ + HAL_PCD_RESET_CB_ID = 0x03, /*!< USB PCD Reset callback ID */ + HAL_PCD_SUSPEND_CB_ID = 0x04, /*!< USB PCD Suspend callback ID */ + HAL_PCD_RESUME_CB_ID = 0x05, /*!< USB PCD Resume callback ID */ + HAL_PCD_CONNECT_CB_ID = 0x06, /*!< USB PCD Connect callback ID */ + HAL_PCD_DISCONNECT_CB_ID = 0x07, /*!< USB PCD Disconnect callback ID */ + + HAL_PCD_MSPINIT_CB_ID = 0x08, /*!< USB PCD MspInit callback ID */ + HAL_PCD_MSPDEINIT_CB_ID = 0x09 /*!< USB PCD MspDeInit callback ID */ + +} HAL_PCD_CallbackIDTypeDef; +/** + * @} + */ + +/** @defgroup HAL_PCD_Callback_pointer_definition HAL USB OTG PCD Callback pointer definition + * @brief HAL USB OTG PCD Callback pointer definition + * @{ + */ + +typedef void (*pPCD_CallbackTypeDef)(PCD_HandleTypeDef *hpcd); /*!< pointer to a common USB OTG PCD callback function */ +typedef void (*pPCD_DataOutStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data OUT Stage callback */ +typedef void (*pPCD_DataInStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data IN Stage callback */ +typedef void (*pPCD_IsoOutIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO OUT Incomplete callback */ +typedef void (*pPCD_IsoInIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO IN Incomplete callback */ +typedef void (*pPCD_LpmCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< pointer to USB OTG PCD LPM callback */ +typedef void (*pPCD_BcdCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< pointer to USB OTG PCD BCD callback */ + +/** + * @} + */ + +HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID, + pPCD_CallbackTypeDef pCallback); + +HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID); + +HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataOutStageCallbackTypeDef pCallback); + +HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd); + +HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataInStageCallbackTypeDef pCallback); + +HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd); + +HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoOutIncpltCallbackTypeDef pCallback); + +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd); + +HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoInIncpltCallbackTypeDef pCallback); + +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd); + +HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd); + +HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ +/** + * @} + */ + +/* I/O operation functions ***************************************************/ +/* Non-Blocking mode: Interrupt */ +/** @addtogroup PCD_Exported_Functions_Group2 Input and Output operation functions + * @{ + */ +HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd); +void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd); +void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd); + +void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd); +void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd); + +void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); +void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); +void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); +void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); +/** + * @} + */ + +/* Peripheral Control functions **********************************************/ +/** @addtogroup PCD_Exported_Functions_Group3 Peripheral Control functions + * @{ + */ +HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address); +HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint16_t ep_mps, uint8_t ep_type); +HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len); +HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len); +HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +HAL_StatusTypeDef HAL_PCD_EP_Abort(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCD_SetTestMode(PCD_HandleTypeDef *hpcd, uint8_t testmode); + +uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); +/** + * @} + */ + +/* Peripheral State functions ************************************************/ +/** @addtogroup PCD_Exported_Functions_Group4 Peripheral State functions + * @{ + */ +PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd); +/** + * @} + */ + +/** + * @} + */ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup PCD_Private_Constants PCD Private Constants + * @{ + */ +/** @defgroup USB_EXTI_Line_Interrupt USB EXTI line interrupt + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +#define USB_OTG_FS_WAKEUP_EXTI_LINE (0x1U << 18) /*!< USB FS EXTI Line WakeUp Interrupt */ +#define USB_OTG_HS_WAKEUP_EXTI_LINE (0x1U << 20) /*!< USB HS EXTI Line WakeUp Interrupt */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ +/** + * @} + */ + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +#ifndef USB_OTG_DOEPINT_OTEPSPR +#define USB_OTG_DOEPINT_OTEPSPR (0x1UL << 5) /*!< Status Phase Received interrupt */ +#endif /* defined USB_OTG_DOEPINT_OTEPSPR */ + +#ifndef USB_OTG_DOEPMSK_OTEPSPRM +#define USB_OTG_DOEPMSK_OTEPSPRM (0x1UL << 5) /*!< Setup Packet Received interrupt mask */ +#endif /* defined USB_OTG_DOEPMSK_OTEPSPRM */ + +#ifndef USB_OTG_DOEPINT_NAK +#define USB_OTG_DOEPINT_NAK (0x1UL << 13) /*!< NAK interrupt */ +#endif /* defined USB_OTG_DOEPINT_NAK */ + +#ifndef USB_OTG_DOEPMSK_NAKM +#define USB_OTG_DOEPMSK_NAKM (0x1UL << 13) /*!< OUT Packet NAK interrupt mask */ +#endif /* defined USB_OTG_DOEPMSK_NAKM */ + +#ifndef USB_OTG_DOEPINT_STPKTRX +#define USB_OTG_DOEPINT_STPKTRX (0x1UL << 15) /*!< Setup Packet Received interrupt */ +#endif /* defined USB_OTG_DOEPINT_STPKTRX */ + +#ifndef USB_OTG_DOEPMSK_NYETM +#define USB_OTG_DOEPMSK_NYETM (0x1UL << 14) /*!< Setup Packet Received interrupt mask */ +#endif /* defined USB_OTG_DOEPMSK_NYETM */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup PCD_Private_Macros PCD Private Macros + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_HAL_PCD_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h index 72ded2b..8eab87e 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h @@ -1,88 +1,88 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd_ex.h - * @author MCD Application Team - * @brief Header file of PCD HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_EX_H -#define STM32F4xx_HAL_PCD_EX_H - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCDEx - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macros -----------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions - * @{ - */ -/** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); -HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); -void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); -void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - - -#endif /* STM32F4xx_HAL_PCD_EX_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd_ex.h + * @author MCD Application Team + * @brief Header file of PCD HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_PCD_EX_H +#define STM32F4xx_HAL_PCD_EX_H + +#ifdef __cplusplus +extern "C" { +#endif /* __cplusplus */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup PCDEx + * @{ + */ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macros -----------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions + * @{ + */ +/** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions + * @{ + */ + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); +HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); +HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); +void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); +#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); +void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + + +#endif /* STM32F4xx_HAL_PCD_EX_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h index d97f255..ab0412d 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h @@ -1,427 +1,427 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr.h - * @author MCD Application Team - * @brief Header file of PWR HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_H -#define __STM32F4xx_HAL_PWR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWR - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup PWR_Exported_Types PWR Exported Types - * @{ - */ - -/** - * @brief PWR PVD configuration structure definition - */ -typedef struct -{ - uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level. - This parameter can be a value of @ref PWR_PVD_detection_level */ - - uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins. - This parameter can be a value of @ref PWR_PVD_Mode */ -}PWR_PVDTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_WakeUp_Pins PWR WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN1 0x00000100U -/** - * @} - */ - -/** @defgroup PWR_PVD_detection_level PWR PVD detection level - * @{ - */ -#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0 -#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1 -#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2 -#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3 -#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4 -#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5 -#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6 -#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7/* External input analog voltage - (Compare internally to VREFINT) */ -/** - * @} - */ - -/** @defgroup PWR_PVD_Mode PWR PVD Mode - * @{ - */ -#define PWR_PVD_MODE_NORMAL 0x00000000U /*!< basic mode is used */ -#define PWR_PVD_MODE_IT_RISING 0x00010001U /*!< External Interrupt Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_IT_FALLING 0x00010002U /*!< External Interrupt Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_IT_RISING_FALLING 0x00010003U /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING 0x00020001U /*!< Event Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_EVENT_FALLING 0x00020002U /*!< Event Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING_FALLING 0x00020003U /*!< Event Mode with Rising/Falling edge trigger detection */ -/** - * @} - */ - - -/** @defgroup PWR_Regulator_state_in_STOP_mode PWR Regulator state in SLEEP/STOP mode - * @{ - */ -#define PWR_MAINREGULATOR_ON 0x00000000U -#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPDS -/** - * @} - */ - -/** @defgroup PWR_SLEEP_mode_entry PWR SLEEP mode entry - * @{ - */ -#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01) -#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_STOP_mode_entry PWR STOP mode entry - * @{ - */ -#define PWR_STOPENTRY_WFI ((uint8_t)0x01) -#define PWR_STOPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_Flag PWR Flag - * @{ - */ -#define PWR_FLAG_WU PWR_CSR_WUF -#define PWR_FLAG_SB PWR_CSR_SBF -#define PWR_FLAG_PVDO PWR_CSR_PVDO -#define PWR_FLAG_BRR PWR_CSR_BRR -#define PWR_FLAG_VOSRDY PWR_CSR_VOSRDY -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_Exported_Macro PWR Exported Macro - * @{ - */ - -/** @brief Check PWR flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event - * was received from the WKUP pin or from the RTC alarm (Alarm A - * or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup. - * An additional wakeup event is detected if the WKUP pin is enabled - * (by setting the EWUP bit) when the WKUP pin level is already high. - * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was - * resumed from StandBy mode. - * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled - * by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode - * For this reason, this bit is equal to 0 after Standby or reset - * until the PVDE bit is set. - * @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset - * when the device wakes up from Standby mode or by a system reset - * or power reset. - * @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage - * scaling output selection is ready. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the PWR's pending flags. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag - * @arg PWR_FLAG_SB: StandBy flag - */ -#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2U) - -/** - * @brief Enable the PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable the PVD EXTI Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_EVENT() (EXTI->EMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE() SET_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Disable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Enable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE() SET_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief Disable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief PVD EXTI line configuration: set rising & falling edge trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief Disable the PVD Extended Interrupt Rising & Falling Trigger. - * This parameter can be: - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief checks whether the specified PVD Exti interrupt flag is set or not. - * @retval EXTI PVD Line Status. - */ -#define __HAL_PWR_PVD_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_PVD)) - -/** - * @brief Clear the PVD Exti flag. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_PVD)) - -/** - * @brief Generates a Software interrupt on PVD EXTI line. - * @retval None - */ -#define __HAL_PWR_PVD_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_PVD)) - -/** - * @} - */ - -/* Include PWR HAL Extension module */ -#include "stm32f4xx_hal_pwr_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWR_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @addtogroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_PWR_DeInit(void); -void HAL_PWR_EnableBkUpAccess(void); -void HAL_PWR_DisableBkUpAccess(void); -/** - * @} - */ - -/** @addtogroup PWR_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -/* Peripheral Control functions **********************************************/ -/* PVD configuration */ -void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD); -void HAL_PWR_EnablePVD(void); -void HAL_PWR_DisablePVD(void); - -/* WakeUp pins configuration */ -void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx); -void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx); - -/* Low Power modes entry */ -void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry); -void HAL_PWR_EnterSTANDBYMode(void); - -/* Power PVD IRQ Handler */ -void HAL_PWR_PVD_IRQHandler(void); -void HAL_PWR_PVDCallback(void); - -/* Cortex System Control functions *******************************************/ -void HAL_PWR_EnableSleepOnExit(void); -void HAL_PWR_DisableSleepOnExit(void); -void HAL_PWR_EnableSEVOnPend(void); -void HAL_PWR_DisableSEVOnPend(void); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWR_Private_Constants PWR Private Constants - * @{ - */ - -/** @defgroup PWR_PVD_EXTI_Line PWR PVD EXTI Line - * @{ - */ -#define PWR_EXTI_LINE_PVD ((uint32_t)EXTI_IMR_MR16) /*!< External interrupt line 16 Connected to the PVD EXTI Line */ -/** - * @} - */ - -/** @defgroup PWR_register_alias_address PWR Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) -#define PWR_CR_OFFSET 0x00U -#define PWR_CSR_OFFSET 0x04U -#define PWR_CR_OFFSET_BB (PWR_OFFSET + PWR_CR_OFFSET) -#define PWR_CSR_OFFSET_BB (PWR_OFFSET + PWR_CSR_OFFSET) -/** - * @} - */ - -/** @defgroup PWR_CR_register_alias PWR CR Register alias address - * @{ - */ -/* --- CR Register ---*/ -/* Alias word address of DBP bit */ -#define DBP_BIT_NUMBER PWR_CR_DBP_Pos -#define CR_DBP_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (DBP_BIT_NUMBER * 4U)) - -/* Alias word address of PVDE bit */ -#define PVDE_BIT_NUMBER PWR_CR_PVDE_Pos -#define CR_PVDE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (PVDE_BIT_NUMBER * 4U)) - -/* Alias word address of VOS bit */ -#define VOS_BIT_NUMBER PWR_CR_VOS_Pos -#define CR_VOS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (VOS_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** @defgroup PWR_CSR_register_alias PWR CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of EWUP bit */ -#define EWUP_BIT_NUMBER PWR_CSR_EWUP_Pos -#define CSR_EWUP_BB (PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (EWUP_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWR_Private_Macros PWR Private Macros - * @{ - */ - -/** @defgroup PWR_IS_PWR_Definitions PWR Private macros to check input parameters - * @{ - */ -#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \ - ((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \ - ((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \ - ((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7)) -#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_PVD_MODE_IT_RISING)|| ((MODE) == PWR_PVD_MODE_IT_FALLING) || \ - ((MODE) == PWR_PVD_MODE_IT_RISING_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING) || \ - ((MODE) == PWR_PVD_MODE_EVENT_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING_FALLING) || \ - ((MODE) == PWR_PVD_MODE_NORMAL)) -#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_ON)) -#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE)) -#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE)) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr.h + * @author MCD Application Team + * @brief Header file of PWR HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_PWR_H +#define __STM32F4xx_HAL_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** @defgroup PWR_Exported_Types PWR Exported Types + * @{ + */ + +/** + * @brief PWR PVD configuration structure definition + */ +typedef struct +{ + uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level. + This parameter can be a value of @ref PWR_PVD_detection_level */ + + uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins. + This parameter can be a value of @ref PWR_PVD_Mode */ +}PWR_PVDTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup PWR_Exported_Constants PWR Exported Constants + * @{ + */ + +/** @defgroup PWR_WakeUp_Pins PWR WakeUp Pins + * @{ + */ +#define PWR_WAKEUP_PIN1 0x00000100U +/** + * @} + */ + +/** @defgroup PWR_PVD_detection_level PWR PVD detection level + * @{ + */ +#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0 +#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1 +#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2 +#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3 +#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4 +#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5 +#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6 +#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7/* External input analog voltage + (Compare internally to VREFINT) */ +/** + * @} + */ + +/** @defgroup PWR_PVD_Mode PWR PVD Mode + * @{ + */ +#define PWR_PVD_MODE_NORMAL 0x00000000U /*!< basic mode is used */ +#define PWR_PVD_MODE_IT_RISING 0x00010001U /*!< External Interrupt Mode with Rising edge trigger detection */ +#define PWR_PVD_MODE_IT_FALLING 0x00010002U /*!< External Interrupt Mode with Falling edge trigger detection */ +#define PWR_PVD_MODE_IT_RISING_FALLING 0x00010003U /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ +#define PWR_PVD_MODE_EVENT_RISING 0x00020001U /*!< Event Mode with Rising edge trigger detection */ +#define PWR_PVD_MODE_EVENT_FALLING 0x00020002U /*!< Event Mode with Falling edge trigger detection */ +#define PWR_PVD_MODE_EVENT_RISING_FALLING 0x00020003U /*!< Event Mode with Rising/Falling edge trigger detection */ +/** + * @} + */ + + +/** @defgroup PWR_Regulator_state_in_STOP_mode PWR Regulator state in SLEEP/STOP mode + * @{ + */ +#define PWR_MAINREGULATOR_ON 0x00000000U +#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPDS +/** + * @} + */ + +/** @defgroup PWR_SLEEP_mode_entry PWR SLEEP mode entry + * @{ + */ +#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01) +#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02) +/** + * @} + */ + +/** @defgroup PWR_STOP_mode_entry PWR STOP mode entry + * @{ + */ +#define PWR_STOPENTRY_WFI ((uint8_t)0x01) +#define PWR_STOPENTRY_WFE ((uint8_t)0x02) +/** + * @} + */ + +/** @defgroup PWR_Flag PWR Flag + * @{ + */ +#define PWR_FLAG_WU PWR_CSR_WUF +#define PWR_FLAG_SB PWR_CSR_SBF +#define PWR_FLAG_PVDO PWR_CSR_PVDO +#define PWR_FLAG_BRR PWR_CSR_BRR +#define PWR_FLAG_VOSRDY PWR_CSR_VOSRDY +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup PWR_Exported_Macro PWR Exported Macro + * @{ + */ + +/** @brief Check PWR flag is set or not. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event + * was received from the WKUP pin or from the RTC alarm (Alarm A + * or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup. + * An additional wakeup event is detected if the WKUP pin is enabled + * (by setting the EWUP bit) when the WKUP pin level is already high. + * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was + * resumed from StandBy mode. + * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled + * by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode + * For this reason, this bit is equal to 0 after Standby or reset + * until the PVDE bit is set. + * @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset + * when the device wakes up from Standby mode or by a system reset + * or power reset. + * @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage + * scaling output selection is ready. + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) + +/** @brief Clear the PWR's pending flags. + * @param __FLAG__ specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + */ +#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2U) + +/** + * @brief Enable the PVD Exti Line 16. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_PVD)) + +/** + * @brief Disable the PVD EXTI Line 16. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_PVD)) + +/** + * @brief Enable event on PVD Exti Line 16. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_ENABLE_EVENT() (EXTI->EMR |= (PWR_EXTI_LINE_PVD)) + +/** + * @brief Disable event on PVD Exti Line 16. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(PWR_EXTI_LINE_PVD)) + +/** + * @brief Enable the PVD Extended Interrupt Rising Trigger. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE() SET_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) + +/** + * @brief Disable the PVD Extended Interrupt Rising Trigger. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) + +/** + * @brief Enable the PVD Extended Interrupt Falling Trigger. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE() SET_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) + + +/** + * @brief Disable the PVD Extended Interrupt Falling Trigger. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) + + +/** + * @brief PVD EXTI line configuration: set rising & falling edge trigger. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE();\ + __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE();\ + }while(0U) + +/** + * @brief Disable the PVD Extended Interrupt Rising & Falling Trigger. + * This parameter can be: + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();\ + __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE();\ + }while(0U) + +/** + * @brief checks whether the specified PVD Exti interrupt flag is set or not. + * @retval EXTI PVD Line Status. + */ +#define __HAL_PWR_PVD_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_PVD)) + +/** + * @brief Clear the PVD Exti flag. + * @retval None. + */ +#define __HAL_PWR_PVD_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_PVD)) + +/** + * @brief Generates a Software interrupt on PVD EXTI line. + * @retval None + */ +#define __HAL_PWR_PVD_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_PVD)) + +/** + * @} + */ + +/* Include PWR HAL Extension module */ +#include "stm32f4xx_hal_pwr_ex.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup PWR_Exported_Functions PWR Exported Functions + * @{ + */ + +/** @addtogroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions + * @{ + */ +/* Initialization and de-initialization functions *****************************/ +void HAL_PWR_DeInit(void); +void HAL_PWR_EnableBkUpAccess(void); +void HAL_PWR_DisableBkUpAccess(void); +/** + * @} + */ + +/** @addtogroup PWR_Exported_Functions_Group2 Peripheral Control functions + * @{ + */ +/* Peripheral Control functions **********************************************/ +/* PVD configuration */ +void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD); +void HAL_PWR_EnablePVD(void); +void HAL_PWR_DisablePVD(void); + +/* WakeUp pins configuration */ +void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx); +void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx); + +/* Low Power modes entry */ +void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry); +void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry); +void HAL_PWR_EnterSTANDBYMode(void); + +/* Power PVD IRQ Handler */ +void HAL_PWR_PVD_IRQHandler(void); +void HAL_PWR_PVDCallback(void); + +/* Cortex System Control functions *******************************************/ +void HAL_PWR_EnableSleepOnExit(void); +void HAL_PWR_DisableSleepOnExit(void); +void HAL_PWR_EnableSEVOnPend(void); +void HAL_PWR_DisableSEVOnPend(void); +/** + * @} + */ + +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup PWR_Private_Constants PWR Private Constants + * @{ + */ + +/** @defgroup PWR_PVD_EXTI_Line PWR PVD EXTI Line + * @{ + */ +#define PWR_EXTI_LINE_PVD ((uint32_t)EXTI_IMR_MR16) /*!< External interrupt line 16 Connected to the PVD EXTI Line */ +/** + * @} + */ + +/** @defgroup PWR_register_alias_address PWR Register alias address + * @{ + */ +/* ------------- PWR registers bit address in the alias region ---------------*/ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) +#define PWR_CR_OFFSET 0x00U +#define PWR_CSR_OFFSET 0x04U +#define PWR_CR_OFFSET_BB (PWR_OFFSET + PWR_CR_OFFSET) +#define PWR_CSR_OFFSET_BB (PWR_OFFSET + PWR_CSR_OFFSET) +/** + * @} + */ + +/** @defgroup PWR_CR_register_alias PWR CR Register alias address + * @{ + */ +/* --- CR Register ---*/ +/* Alias word address of DBP bit */ +#define DBP_BIT_NUMBER PWR_CR_DBP_Pos +#define CR_DBP_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (DBP_BIT_NUMBER * 4U)) + +/* Alias word address of PVDE bit */ +#define PVDE_BIT_NUMBER PWR_CR_PVDE_Pos +#define CR_PVDE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (PVDE_BIT_NUMBER * 4U)) + +/* Alias word address of VOS bit */ +#define VOS_BIT_NUMBER PWR_CR_VOS_Pos +#define CR_VOS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (VOS_BIT_NUMBER * 4U)) +/** + * @} + */ + +/** @defgroup PWR_CSR_register_alias PWR CSR Register alias address + * @{ + */ +/* --- CSR Register ---*/ +/* Alias word address of EWUP bit */ +#define EWUP_BIT_NUMBER PWR_CSR_EWUP_Pos +#define CSR_EWUP_BB (PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (EWUP_BIT_NUMBER * 4U)) +/** + * @} + */ + +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/** @defgroup PWR_Private_Macros PWR Private Macros + * @{ + */ + +/** @defgroup PWR_IS_PWR_Definitions PWR Private macros to check input parameters + * @{ + */ +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \ + ((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \ + ((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \ + ((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7)) +#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_PVD_MODE_IT_RISING)|| ((MODE) == PWR_PVD_MODE_IT_FALLING) || \ + ((MODE) == PWR_PVD_MODE_IT_RISING_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING) || \ + ((MODE) == PWR_PVD_MODE_EVENT_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING_FALLING) || \ + ((MODE) == PWR_PVD_MODE_NORMAL)) +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \ + ((REGULATOR) == PWR_LOWPOWERREGULATOR_ON)) +#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE)) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE)) +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + + +#endif /* __STM32F4xx_HAL_PWR_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h index 57fd4d9..7b632a5 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h @@ -1,340 +1,340 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr_ex.h - * @author MCD Application Team - * @brief Header file of PWR HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_EX_H -#define __STM32F4xx_HAL_PWR_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWREx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @defgroup PWREx_Regulator_state_in_UnderDrive_mode PWREx Regulator state in UnderDrive mode - * @{ - */ -#define PWR_MAINREGULATOR_UNDERDRIVE_ON PWR_CR_MRUDS -#define PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON ((uint32_t)(PWR_CR_LPDS | PWR_CR_LPUDS)) -/** - * @} - */ - -/** @defgroup PWREx_Over_Under_Drive_Flag PWREx Over Under Drive Flag - * @{ - */ -#define PWR_FLAG_ODRDY PWR_CSR_ODRDY -#define PWR_FLAG_ODSWRDY PWR_CSR_ODSWRDY -#define PWR_FLAG_UDRDY PWR_CSR_UDSWRDY -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** @defgroup PWREx_Regulator_Voltage_Scale PWREx Regulator Voltage Scale - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK = 168 MHz. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 0x00000000U /* Scale 2 mode: the maximum value of fHCLK = 144 MHz. */ -#else -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK is 168 MHz. It can be extended to - 180 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 PWR_CR_VOS_1 /* Scale 2 mode: the maximum value of fHCLK is 144 MHz. It can be extended to - 168 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE3 PWR_CR_VOS_0 /* Scale 3 mode: the maximum value of fHCLK is 120 MHz. */ -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ -/** - * @} - */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup PWREx_WakeUp_Pins PWREx WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN2 0x00000080U -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define PWR_WAKEUP_PIN3 0x00000040U -#endif /* STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F410xx || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#else -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to enable or disable the Over drive mode. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVE_ENABLE() (*(__IO uint32_t *) CR_ODEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVE_DISABLE() (*(__IO uint32_t *) CR_ODEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Over drive switching. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVESWITCHING_ENABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVESWITCHING_DISABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Under drive mode. - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main regulator or the low power regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - */ -#define __HAL_PWR_UNDERDRIVE_ENABLE() (PWR->CR |= (uint32_t)PWR_CR_UDEN) -#define __HAL_PWR_UNDERDRIVE_DISABLE() (PWR->CR &= (uint32_t)(~PWR_CR_UDEN)) - -/** @brief Check PWR flag is set or not. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_ODRDY: This flag indicates that the Over-drive mode - * is ready - * @arg PWR_FLAG_ODSWRDY: This flag indicates that the Over-drive mode - * switching is ready - * @arg PWR_FLAG_UDRDY: This flag indicates that the Under-drive mode - * is enabled in Stop mode - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_ODRUDR_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the Under-Drive Ready flag. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_CLEAR_ODRUDR_FLAG() (PWR->CSR |= PWR_FLAG_UDRDY) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWREx_Exported_Functions PWREx Exported Functions - * @{ - */ - -/** @addtogroup PWREx_Exported_Functions_Group1 - * @{ - */ -void HAL_PWREx_EnableFlashPowerDown(void); -void HAL_PWREx_DisableFlashPowerDown(void); -HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void); -HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void); -uint32_t HAL_PWREx_GetVoltageRange(void); -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -void HAL_PWREx_EnableMainRegulatorLowVoltage(void); -void HAL_PWREx_DisableMainRegulatorLowVoltage(void); -void HAL_PWREx_EnableLowRegulatorLowVoltage(void); -void HAL_PWREx_DisableLowRegulatorLowVoltage(void); -#endif /* STM32F410xx || STM32F401xC || STM32F401xE || STM32F411xE || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWREx_Private_Constants PWREx Private Constants - * @{ - */ - -/** @defgroup PWREx_register_alias_address PWREx Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -/* --- CR Register ---*/ -/* Alias word address of FPDS bit */ -#define FPDS_BIT_NUMBER PWR_CR_FPDS_Pos -#define CR_FPDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (FPDS_BIT_NUMBER * 4U)) - -/* Alias word address of ODEN bit */ -#define ODEN_BIT_NUMBER PWR_CR_ODEN_Pos -#define CR_ODEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODEN_BIT_NUMBER * 4U)) - -/* Alias word address of ODSWEN bit */ -#define ODSWEN_BIT_NUMBER PWR_CR_ODSWEN_Pos -#define CR_ODSWEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODSWEN_BIT_NUMBER * 4U)) - -/* Alias word address of MRLVDS bit */ -#define MRLVDS_BIT_NUMBER PWR_CR_MRLVDS_Pos -#define CR_MRLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (MRLVDS_BIT_NUMBER * 4U)) - -/* Alias word address of LPLVDS bit */ -#define LPLVDS_BIT_NUMBER PWR_CR_LPLVDS_Pos -#define CR_LPLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (LPLVDS_BIT_NUMBER * 4U)) - - /** - * @} - */ - -/** @defgroup PWREx_CSR_register_alias PWRx CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of BRE bit */ -#define BRE_BIT_NUMBER PWR_CSR_BRE_Pos -#define CSR_BRE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (BRE_BIT_NUMBER * 4U)) - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWREx_Private_Macros PWREx Private Macros - * @{ - */ - -/** @defgroup PWREx_IS_PWR_Definitions PWREx Private macros to check input parameters - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_PWR_REGULATOR_UNDERDRIVE(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_UNDERDRIVE_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2)) -#else -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE3)) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F446xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2)) -#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2) || \ - ((PIN) == PWR_WAKEUP_PIN3)) -#else -#define IS_PWR_WAKEUP_PIN(PIN) ((PIN) == PWR_WAKEUP_PIN1) -#endif /* STM32F446xx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_EX_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr_ex.h + * @author MCD Application Team + * @brief Header file of PWR HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_PWR_EX_H +#define __STM32F4xx_HAL_PWR_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup PWREx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup PWREx_Exported_Constants PWREx Exported Constants + * @{ + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/** @defgroup PWREx_Regulator_state_in_UnderDrive_mode PWREx Regulator state in UnderDrive mode + * @{ + */ +#define PWR_MAINREGULATOR_UNDERDRIVE_ON PWR_CR_MRUDS +#define PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON ((uint32_t)(PWR_CR_LPDS | PWR_CR_LPUDS)) +/** + * @} + */ + +/** @defgroup PWREx_Over_Under_Drive_Flag PWREx Over Under Drive Flag + * @{ + */ +#define PWR_FLAG_ODRDY PWR_CSR_ODRDY +#define PWR_FLAG_ODSWRDY PWR_CSR_ODSWRDY +#define PWR_FLAG_UDRDY PWR_CSR_UDSWRDY +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +/** @defgroup PWREx_Regulator_Voltage_Scale PWREx Regulator Voltage Scale + * @{ + */ +#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) +#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK = 168 MHz. */ +#define PWR_REGULATOR_VOLTAGE_SCALE2 0x00000000U /* Scale 2 mode: the maximum value of fHCLK = 144 MHz. */ +#else +#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK is 168 MHz. It can be extended to + 180 MHz by activating the over-drive mode. */ +#define PWR_REGULATOR_VOLTAGE_SCALE2 PWR_CR_VOS_1 /* Scale 2 mode: the maximum value of fHCLK is 144 MHz. It can be extended to + 168 MHz by activating the over-drive mode. */ +#define PWR_REGULATOR_VOLTAGE_SCALE3 PWR_CR_VOS_0 /* Scale 3 mode: the maximum value of fHCLK is 120 MHz. */ +#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ +/** + * @} + */ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup PWREx_WakeUp_Pins PWREx WakeUp Pins + * @{ + */ +#define PWR_WAKEUP_PIN2 0x00000080U +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +#define PWR_WAKEUP_PIN3 0x00000040U +#endif /* STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Zx || STM32F412Vx || \ + STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +/** + * @} + */ +#endif /* STM32F410xx || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup PWREx_Exported_Constants PWREx Exported Constants + * @{ + */ + +#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) +/** @brief macros configure the main internal regulator output voltage. + * @param __REGULATOR__ specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption when the device does + * not operate at the maximum frequency (refer to the datasheets for more details). + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode + * @retval None + */ +#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ + __IO uint32_t tmpreg = 0x00U; \ + MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ + UNUSED(tmpreg); \ + } while(0U) +#else +/** @brief macros configure the main internal regulator output voltage. + * @param __REGULATOR__ specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption when the device does + * not operate at the maximum frequency (refer to the datasheets for more details). + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode + * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode + * @retval None + */ +#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ + __IO uint32_t tmpreg = 0x00U; \ + MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macros to enable or disable the Over drive mode. + * @note These macros can be used only for STM32F42xx/STM3243xx devices. + */ +#define __HAL_PWR_OVERDRIVE_ENABLE() (*(__IO uint32_t *) CR_ODEN_BB = ENABLE) +#define __HAL_PWR_OVERDRIVE_DISABLE() (*(__IO uint32_t *) CR_ODEN_BB = DISABLE) + +/** @brief Macros to enable or disable the Over drive switching. + * @note These macros can be used only for STM32F42xx/STM3243xx devices. + */ +#define __HAL_PWR_OVERDRIVESWITCHING_ENABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = ENABLE) +#define __HAL_PWR_OVERDRIVESWITCHING_DISABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = DISABLE) + +/** @brief Macros to enable or disable the Under drive mode. + * @note This mode is enabled only with STOP low power mode. + * In this mode, the 1.2V domain is preserved in reduced leakage mode. This + * mode is only available when the main regulator or the low power regulator + * is in low voltage mode. + * @note If the Under-drive mode was enabled, it is automatically disabled after + * exiting Stop mode. + * When the voltage regulator operates in Under-drive mode, an additional + * startup delay is induced when waking up from Stop mode. + */ +#define __HAL_PWR_UNDERDRIVE_ENABLE() (PWR->CR |= (uint32_t)PWR_CR_UDEN) +#define __HAL_PWR_UNDERDRIVE_DISABLE() (PWR->CR &= (uint32_t)(~PWR_CR_UDEN)) + +/** @brief Check PWR flag is set or not. + * @note These macros can be used only for STM32F42xx/STM3243xx devices. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_ODRDY: This flag indicates that the Over-drive mode + * is ready + * @arg PWR_FLAG_ODSWRDY: This flag indicates that the Over-drive mode + * switching is ready + * @arg PWR_FLAG_UDRDY: This flag indicates that the Under-drive mode + * is enabled in Stop mode + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_PWR_GET_ODRUDR_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) + +/** @brief Clear the Under-Drive Ready flag. + * @note These macros can be used only for STM32F42xx/STM3243xx devices. + */ +#define __HAL_PWR_CLEAR_ODRUDR_FLAG() (PWR->CSR |= PWR_FLAG_UDRDY) + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup PWREx_Exported_Functions PWREx Exported Functions + * @{ + */ + +/** @addtogroup PWREx_Exported_Functions_Group1 + * @{ + */ +void HAL_PWREx_EnableFlashPowerDown(void); +void HAL_PWREx_DisableFlashPowerDown(void); +HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void); +HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void); +uint32_t HAL_PWREx_GetVoltageRange(void); +HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling); + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ + defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +void HAL_PWREx_EnableMainRegulatorLowVoltage(void); +void HAL_PWREx_DisableMainRegulatorLowVoltage(void); +void HAL_PWREx_EnableLowRegulatorLowVoltage(void); +void HAL_PWREx_DisableLowRegulatorLowVoltage(void); +#endif /* STM32F410xx || STM32F401xC || STM32F401xE || STM32F411xE || STM32F412Zx || STM32F412Vx ||\ + STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void); +HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void); +HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup PWREx_Private_Constants PWREx Private Constants + * @{ + */ + +/** @defgroup PWREx_register_alias_address PWREx Register alias address + * @{ + */ +/* ------------- PWR registers bit address in the alias region ---------------*/ +/* --- CR Register ---*/ +/* Alias word address of FPDS bit */ +#define FPDS_BIT_NUMBER PWR_CR_FPDS_Pos +#define CR_FPDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (FPDS_BIT_NUMBER * 4U)) + +/* Alias word address of ODEN bit */ +#define ODEN_BIT_NUMBER PWR_CR_ODEN_Pos +#define CR_ODEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODEN_BIT_NUMBER * 4U)) + +/* Alias word address of ODSWEN bit */ +#define ODSWEN_BIT_NUMBER PWR_CR_ODSWEN_Pos +#define CR_ODSWEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODSWEN_BIT_NUMBER * 4U)) + +/* Alias word address of MRLVDS bit */ +#define MRLVDS_BIT_NUMBER PWR_CR_MRLVDS_Pos +#define CR_MRLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (MRLVDS_BIT_NUMBER * 4U)) + +/* Alias word address of LPLVDS bit */ +#define LPLVDS_BIT_NUMBER PWR_CR_LPLVDS_Pos +#define CR_LPLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (LPLVDS_BIT_NUMBER * 4U)) + + /** + * @} + */ + +/** @defgroup PWREx_CSR_register_alias PWRx CSR Register alias address + * @{ + */ +/* --- CSR Register ---*/ +/* Alias word address of BRE bit */ +#define BRE_BIT_NUMBER PWR_CSR_BRE_Pos +#define CSR_BRE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (BRE_BIT_NUMBER * 4U)) + +/** + * @} + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup PWREx_Private_Macros PWREx Private Macros + * @{ + */ + +/** @defgroup PWREx_IS_PWR_Definitions PWREx Private macros to check input parameters + * @{ + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define IS_PWR_REGULATOR_UNDERDRIVE(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_UNDERDRIVE_ON) || \ + ((REGULATOR) == PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) +#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ + ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2)) +#else +#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ + ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2) || \ + ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE3)) +#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ + +#if defined(STM32F446xx) +#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2)) +#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2) || \ + ((PIN) == PWR_WAKEUP_PIN3)) +#else +#define IS_PWR_WAKEUP_PIN(PIN) ((PIN) == PWR_WAKEUP_PIN1) +#endif /* STM32F446xx */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + + +#endif /* __STM32F4xx_HAL_PWR_EX_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h index dcf5814..908432d 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h @@ -1,1459 +1,1459 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc.h - * @author MCD Application Team - * @brief Header file of RCC HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_H -#define __STM32F4xx_HAL_RCC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include RCC HAL Extended module */ -/* (include on top of file since RCC structures are defined in extended file) */ -#include "stm32f4xx_hal_rcc_ex.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Types RCC Exported Types - * @{ - */ - -/** - * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition - */ -typedef struct -{ - uint32_t OscillatorType; /*!< The oscillators to be configured. - This parameter can be a value of @ref RCC_Oscillator_Type */ - - uint32_t HSEState; /*!< The new state of the HSE. - This parameter can be a value of @ref RCC_HSE_Config */ - - uint32_t LSEState; /*!< The new state of the LSE. - This parameter can be a value of @ref RCC_LSE_Config */ - - uint32_t HSIState; /*!< The new state of the HSI. - This parameter can be a value of @ref RCC_HSI_Config */ - - uint32_t HSICalibrationValue; /*!< The HSI calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT). - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ - - uint32_t LSIState; /*!< The new state of the LSI. - This parameter can be a value of @ref RCC_LSI_Config */ - - RCC_PLLInitTypeDef PLL; /*!< PLL structure parameters */ -}RCC_OscInitTypeDef; - -/** - * @brief RCC System, AHB and APB busses clock configuration structure definition - */ -typedef struct -{ - uint32_t ClockType; /*!< The clock to be configured. - This parameter can be a value of @ref RCC_System_Clock_Type */ - - uint32_t SYSCLKSource; /*!< The clock source (SYSCLKS) used as system clock. - This parameter can be a value of @ref RCC_System_Clock_Source */ - - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_AHB_Clock_Source */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - -}RCC_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_Oscillator_Type Oscillator Type - * @{ - */ -#define RCC_OSCILLATORTYPE_NONE 0x00000000U -#define RCC_OSCILLATORTYPE_HSE 0x00000001U -#define RCC_OSCILLATORTYPE_HSI 0x00000002U -#define RCC_OSCILLATORTYPE_LSE 0x00000004U -#define RCC_OSCILLATORTYPE_LSI 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_HSE_Config HSE Config - * @{ - */ -#define RCC_HSE_OFF 0x00000000U -#define RCC_HSE_ON RCC_CR_HSEON -#define RCC_HSE_BYPASS ((uint32_t)(RCC_CR_HSEBYP | RCC_CR_HSEON)) -/** - * @} - */ - -/** @defgroup RCC_LSE_Config LSE Config - * @{ - */ -#define RCC_LSE_OFF 0x00000000U -#define RCC_LSE_ON RCC_BDCR_LSEON -#define RCC_LSE_BYPASS ((uint32_t)(RCC_BDCR_LSEBYP | RCC_BDCR_LSEON)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Config HSI Config - * @{ - */ -#define RCC_HSI_OFF ((uint8_t)0x00) -#define RCC_HSI_ON ((uint8_t)0x01) - -#define RCC_HSICALIBRATION_DEFAULT 0x10U /* Default HSI calibration trimming value */ -/** - * @} - */ - -/** @defgroup RCC_LSI_Config LSI Config - * @{ - */ -#define RCC_LSI_OFF ((uint8_t)0x00) -#define RCC_LSI_ON ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup RCC_PLL_Config PLL Config - * @{ - */ -#define RCC_PLL_NONE ((uint8_t)0x00) -#define RCC_PLL_OFF ((uint8_t)0x01) -#define RCC_PLL_ON ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup RCC_PLLP_Clock_Divider PLLP Clock Divider - * @{ - */ -#define RCC_PLLP_DIV2 0x00000002U -#define RCC_PLLP_DIV4 0x00000004U -#define RCC_PLLP_DIV6 0x00000006U -#define RCC_PLLP_DIV8 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_PLL_Clock_Source PLL Clock Source - * @{ - */ -#define RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI -#define RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Type System Clock Type - * @{ - */ -#define RCC_CLOCKTYPE_SYSCLK 0x00000001U -#define RCC_CLOCKTYPE_HCLK 0x00000002U -#define RCC_CLOCKTYPE_PCLK1 0x00000004U -#define RCC_CLOCKTYPE_PCLK2 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source System Clock Source - * @note The RCC_SYSCLKSOURCE_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI -#define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE -#define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL -#define RCC_SYSCLKSOURCE_PLLRCLK ((uint32_t)(RCC_CFGR_SW_0 | RCC_CFGR_SW_1)) -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source_Status System Clock Source Status - * @note The RCC_SYSCLKSOURCE_STATUS_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLRCLK ((uint32_t)(RCC_CFGR_SWS_0 | RCC_CFGR_SWS_1)) /*!< PLLR used as system clock */ -/** - * @} - */ - -/** @defgroup RCC_AHB_Clock_Source AHB Clock Source - * @{ - */ -#define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 -#define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 -#define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 -#define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 -#define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 -#define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 -#define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 -#define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 -#define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 -/** - * @} - */ - -/** @defgroup RCC_APB1_APB2_Clock_Source APB1/APB2 Clock Source - * @{ - */ -#define RCC_HCLK_DIV1 RCC_CFGR_PPRE1_DIV1 -#define RCC_HCLK_DIV2 RCC_CFGR_PPRE1_DIV2 -#define RCC_HCLK_DIV4 RCC_CFGR_PPRE1_DIV4 -#define RCC_HCLK_DIV8 RCC_CFGR_PPRE1_DIV8 -#define RCC_HCLK_DIV16 RCC_CFGR_PPRE1_DIV16 -/** - * @} - */ - -/** @defgroup RCC_RTC_Clock_Source RTC Clock Source - * @{ - */ -#define RCC_RTCCLKSOURCE_NO_CLK 0x00000000U -#define RCC_RTCCLKSOURCE_LSE 0x00000100U -#define RCC_RTCCLKSOURCE_LSI 0x00000200U -#define RCC_RTCCLKSOURCE_HSE_DIVX 0x00000300U -#define RCC_RTCCLKSOURCE_HSE_DIV2 0x00020300U -#define RCC_RTCCLKSOURCE_HSE_DIV3 0x00030300U -#define RCC_RTCCLKSOURCE_HSE_DIV4 0x00040300U -#define RCC_RTCCLKSOURCE_HSE_DIV5 0x00050300U -#define RCC_RTCCLKSOURCE_HSE_DIV6 0x00060300U -#define RCC_RTCCLKSOURCE_HSE_DIV7 0x00070300U -#define RCC_RTCCLKSOURCE_HSE_DIV8 0x00080300U -#define RCC_RTCCLKSOURCE_HSE_DIV9 0x00090300U -#define RCC_RTCCLKSOURCE_HSE_DIV10 0x000A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV11 0x000B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV12 0x000C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV13 0x000D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV14 0x000E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV15 0x000F0300U -#define RCC_RTCCLKSOURCE_HSE_DIV16 0x00100300U -#define RCC_RTCCLKSOURCE_HSE_DIV17 0x00110300U -#define RCC_RTCCLKSOURCE_HSE_DIV18 0x00120300U -#define RCC_RTCCLKSOURCE_HSE_DIV19 0x00130300U -#define RCC_RTCCLKSOURCE_HSE_DIV20 0x00140300U -#define RCC_RTCCLKSOURCE_HSE_DIV21 0x00150300U -#define RCC_RTCCLKSOURCE_HSE_DIV22 0x00160300U -#define RCC_RTCCLKSOURCE_HSE_DIV23 0x00170300U -#define RCC_RTCCLKSOURCE_HSE_DIV24 0x00180300U -#define RCC_RTCCLKSOURCE_HSE_DIV25 0x00190300U -#define RCC_RTCCLKSOURCE_HSE_DIV26 0x001A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV27 0x001B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV28 0x001C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV29 0x001D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV30 0x001E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV31 0x001F0300U -/** - * @} - */ - -/** @defgroup RCC_MCO_Index MCO Index - * @{ - */ -#define RCC_MCO1 0x00000000U -#define RCC_MCO2 0x00000001U -/** - * @} - */ - -/** @defgroup RCC_MCO1_Clock_Source MCO1 Clock Source - * @{ - */ -#define RCC_MCO1SOURCE_HSI 0x00000000U -#define RCC_MCO1SOURCE_LSE RCC_CFGR_MCO1_0 -#define RCC_MCO1SOURCE_HSE RCC_CFGR_MCO1_1 -#define RCC_MCO1SOURCE_PLLCLK RCC_CFGR_MCO1 -/** - * @} - */ - -/** @defgroup RCC_MCOx_Clock_Prescaler MCOx Clock Prescaler - * @{ - */ -#define RCC_MCODIV_1 0x00000000U -#define RCC_MCODIV_2 RCC_CFGR_MCO1PRE_2 -#define RCC_MCODIV_3 ((uint32_t)RCC_CFGR_MCO1PRE_0 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_4 ((uint32_t)RCC_CFGR_MCO1PRE_1 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_5 RCC_CFGR_MCO1PRE -/** - * @} - */ - -/** @defgroup RCC_Interrupt Interrupts - * @{ - */ -#define RCC_IT_LSIRDY ((uint8_t)0x01) -#define RCC_IT_LSERDY ((uint8_t)0x02) -#define RCC_IT_HSIRDY ((uint8_t)0x04) -#define RCC_IT_HSERDY ((uint8_t)0x08) -#define RCC_IT_PLLRDY ((uint8_t)0x10) -#define RCC_IT_PLLI2SRDY ((uint8_t)0x20) -#define RCC_IT_CSS ((uint8_t)0x80) -/** - * @} - */ - -/** @defgroup RCC_Flag Flags - * Elements values convention: 0XXYYYYYb - * - YYYYY : Flag position in the register - * - 0XX : Register index - * - 01: CR register - * - 10: BDCR register - * - 11: CSR register - * @{ - */ -/* Flags in the CR register */ -#define RCC_FLAG_HSIRDY ((uint8_t)0x21) -#define RCC_FLAG_HSERDY ((uint8_t)0x31) -#define RCC_FLAG_PLLRDY ((uint8_t)0x39) -#define RCC_FLAG_PLLI2SRDY ((uint8_t)0x3B) - -/* Flags in the BDCR register */ -#define RCC_FLAG_LSERDY ((uint8_t)0x41) - -/* Flags in the CSR register */ -#define RCC_FLAG_LSIRDY ((uint8_t)0x61) -#define RCC_FLAG_BORRST ((uint8_t)0x79) -#define RCC_FLAG_PINRST ((uint8_t)0x7A) -#define RCC_FLAG_PORRST ((uint8_t)0x7B) -#define RCC_FLAG_SFTRST ((uint8_t)0x7C) -#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) -#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) -#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOA_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOAEN)) -#define __HAL_RCC_GPIOB_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOBEN)) -#define __HAL_RCC_GPIOC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOCEN)) -#define __HAL_RCC_GPIOH_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOHEN)) -#define __HAL_RCC_DMA1_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA1EN)) -#define __HAL_RCC_DMA2_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2EN)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) != RESET) -#define __HAL_RCC_GPIOB_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) != RESET) -#define __HAL_RCC_GPIOC_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) != RESET) -#define __HAL_RCC_GPIOH_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) != RESET) -#define __HAL_RCC_DMA1_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) != RESET) -#define __HAL_RCC_DMA2_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) != RESET) - -#define __HAL_RCC_GPIOA_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) == RESET) -#define __HAL_RCC_GPIOB_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) == RESET) -#define __HAL_RCC_GPIOC_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) == RESET) -#define __HAL_RCC_GPIOH_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) == RESET) -#define __HAL_RCC_DMA1_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) == RESET) -#define __HAL_RCC_DMA2_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_WWDG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_PWR_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM5EN)) -#define __HAL_RCC_WWDG_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_WWDGEN)) -#define __HAL_RCC_SPI2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN)) -#define __HAL_RCC_USART2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART2EN)) -#define __HAL_RCC_I2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN)) -#define __HAL_RCC_I2C2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C2EN)) -#define __HAL_RCC_PWR_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_PWREN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) != RESET) -#define __HAL_RCC_WWDG_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) != RESET) -#define __HAL_RCC_SPI2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) != RESET) -#define __HAL_RCC_USART2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) != RESET) -#define __HAL_RCC_I2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) != RESET) -#define __HAL_RCC_I2C2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) != RESET) -#define __HAL_RCC_PWR_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) != RESET) - -#define __HAL_RCC_TIM5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) == RESET) -#define __HAL_RCC_WWDG_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) == RESET) -#define __HAL_RCC_SPI2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) == RESET) -#define __HAL_RCC_USART2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) == RESET) -#define __HAL_RCC_I2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) == RESET) -#define __HAL_RCC_I2C2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) == RESET) -#define __HAL_RCC_PWR_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM11_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM1EN)) -#define __HAL_RCC_USART1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN)) -#define __HAL_RCC_USART6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART6EN)) -#define __HAL_RCC_ADC1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN)) -#define __HAL_RCC_SPI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN)) -#define __HAL_RCC_SYSCFG_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SYSCFGEN)) -#define __HAL_RCC_TIM9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM9EN)) -#define __HAL_RCC_TIM11_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM11EN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) != RESET) -#define __HAL_RCC_USART1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) != RESET) -#define __HAL_RCC_USART6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) != RESET) -#define __HAL_RCC_ADC1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) != RESET) -#define __HAL_RCC_SPI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) != RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) != RESET) -#define __HAL_RCC_TIM9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) != RESET) -#define __HAL_RCC_TIM11_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) != RESET) - -#define __HAL_RCC_TIM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) == RESET) -#define __HAL_RCC_USART1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) == RESET) -#define __HAL_RCC_USART6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) == RESET) -#define __HAL_RCC_ADC1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) == RESET) -#define __HAL_RCC_SPI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) == RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) == RESET) -#define __HAL_RCC_TIM9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) == RESET) -#define __HAL_RCC_TIM11_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOA_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2RST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOA_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2RST)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_PWRRST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_PWRRST)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM11RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_TIM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM11RST)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2LPEN)) - -#define __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2LPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_PWRLPEN)) - -#define __HAL_RCC_TIM5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_PWRLPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM11LPEN)) - -#define __HAL_RCC_TIM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM11LPEN)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Configuration HSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal High Speed oscillator (HSI). - * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. - * It is used (enabled by hardware) as system clock source after startup - * from Reset, wake-up from STOP and STANDBY mode, or in case of failure - * of the HSE used directly or indirectly as system clock (if the Clock - * Security System CSS is enabled). - * @note HSI can not be stopped if it is used as system clock source. In this case, - * you have to select another source of the system clock then stop the HSI. - * @note After enabling the HSI, the application software should wait on HSIRDY - * flag to be set indicating that HSI clock is stable and can be used as - * system clock source. - * This parameter can be: ENABLE or DISABLE. - * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator - * clock cycles. - */ -#define __HAL_RCC_HSI_ENABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = ENABLE) -#define __HAL_RCC_HSI_DISABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = DISABLE) - -/** @brief Macro to adjust the Internal High Speed oscillator (HSI) calibration value. - * @note The calibration is used to compensate for the variations in voltage - * and temperature that influence the frequency of the internal HSI RC. - * @param __HSICalibrationValue__ specifies the calibration trimming value. - * (default is RCC_HSICALIBRATION_DEFAULT). - * This parameter must be a number between 0 and 0x1F. - */ -#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICalibrationValue__) (MODIFY_REG(RCC->CR,\ - RCC_CR_HSITRIM, (uint32_t)(__HSICalibrationValue__) << RCC_CR_HSITRIM_Pos)) -/** - * @} - */ - -/** @defgroup RCC_LSI_Configuration LSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal Low Speed oscillator (LSI). - * @note After enabling the LSI, the application software should wait on - * LSIRDY flag to be set indicating that LSI clock is stable and can - * be used to clock the IWDG and/or the RTC. - * @note LSI can not be disabled if the IWDG is running. - * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator - * clock cycles. - */ -#define __HAL_RCC_LSI_ENABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = ENABLE) -#define __HAL_RCC_LSI_DISABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_HSE_Configuration HSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External High Speed oscillator (HSE). - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not supported by this macro. - * User should request a transition to HSE Off first and then HSE On or HSE Bypass. - * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application - * software should wait on HSERDY flag to be set indicating that HSE clock - * is stable and can be used to clock the PLL and/or system clock. - * @note HSE state can not be changed if it is used directly or through the - * PLL as system clock. In this case, you have to select another source - * of the system clock then change the HSE state (ex. disable it). - * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. - * @note This function reset the CSSON bit, so if the clock security system(CSS) - * was previously enabled you have to enable it again after calling this - * function. - * @param __STATE__ specifies the new state of the HSE. - * This parameter can be one of the following values: - * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after - * 6 HSE oscillator clock cycles. - * @arg RCC_HSE_ON: turn ON the HSE oscillator. - * @arg RCC_HSE_BYPASS: HSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_HSE_CONFIG(__STATE__) \ - do { \ - if ((__STATE__) == RCC_HSE_ON) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else if ((__STATE__) == RCC_HSE_BYPASS) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_LSE_Configuration LSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External Low Speed oscillator (LSE). - * @note Transition LSE Bypass to LSE On and LSE On to LSE Bypass are not supported by this macro. - * User should request a transition to LSE Off first and then LSE On or LSE Bypass. - * @note As the LSE is in the Backup domain and write access is denied to - * this domain after reset, you have to enable write access using - * HAL_PWR_EnableBkUpAccess() function before to configure the LSE - * (to be done once after reset). - * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application - * software should wait on LSERDY flag to be set indicating that LSE clock - * is stable and can be used to clock the RTC. - * @param __STATE__ specifies the new state of the LSE. - * This parameter can be one of the following values: - * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after - * 6 LSE oscillator clock cycles. - * @arg RCC_LSE_ON: turn ON the LSE oscillator. - * @arg RCC_LSE_BYPASS: LSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_LSE_CONFIG(__STATE__) \ - do { \ - if((__STATE__) == RCC_LSE_ON) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else if((__STATE__) == RCC_LSE_BYPASS) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_Internal_RTC_Clock_Configuration RTC Clock Configuration - * @{ - */ - -/** @brief Macros to enable or disable the RTC clock. - * @note These macros must be used only after the RTC clock source was selected. - */ -#define __HAL_RCC_RTC_ENABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = ENABLE) -#define __HAL_RCC_RTC_DISABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = DISABLE) - -/** @brief Macros to configure the RTC clock (RTCCLK). - * @note As the RTC clock configuration bits are in the Backup domain and write - * access is denied to this domain after reset, you have to enable write - * access using the Power Backup Access macro before to configure - * the RTC clock source (to be done once after reset). - * @note Once the RTC clock is configured it can't be changed unless the - * Backup domain is reset using __HAL_RCC_BackupReset_RELEASE() macro, or by - * a Power On Reset (POR). - * @param __RTCCLKSource__ specifies the RTC clock source. - * This parameter can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK : No clock selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSE : LSE selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSI : LSI selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - * @note If the LSE or LSI is used as RTC clock source, the RTC continues to - * work in STOP and STANDBY modes, and can be used as wake-up source. - * However, when the HSE clock is used as RTC clock source, the RTC - * cannot be used in STOP and STANDBY modes. - * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as - * RTC clock source). - */ -#define __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__) (((__RTCCLKSource__) & RCC_BDCR_RTCSEL) == RCC_BDCR_RTCSEL) ? \ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, ((__RTCCLKSource__) & 0xFFFFCFFU)) : CLEAR_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) - -#define __HAL_RCC_RTC_CONFIG(__RTCCLKSource__) do { __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__); \ - RCC->BDCR |= ((__RTCCLKSource__) & 0x00000FFFU); \ - } while(0U) - -/** @brief Macro to get the RTC clock source. - * @retval The clock source can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)) - -/** - * @brief Get the RTC and HSE clock divider (RTCPRE). - * @retval Returned value can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_HSE_PRESCALER() (READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) | RCC_BDCR_RTCSEL) - -/** @brief Macros to force or release the Backup domain reset. - * @note This function resets the RTC peripheral (including the backup registers) - * and the RTC clock source selection in RCC_CSR register. - * @note The BKPSRAM is not affected by this reset. - */ -#define __HAL_RCC_BACKUPRESET_FORCE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = ENABLE) -#define __HAL_RCC_BACKUPRESET_RELEASE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_PLL_Configuration PLL Configuration - * @{ - */ - -/** @brief Macros to enable or disable the main PLL. - * @note After enabling the main PLL, the application software should wait on - * PLLRDY flag to be set indicating that PLL clock is stable and can - * be used as system clock source. - * @note The main PLL can not be disabled if it is used as system clock source - * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLL_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = ENABLE) -#define __HAL_RCC_PLL_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = DISABLE) - -/** @brief Macro to configure the PLL clock source. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLSOURCE__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * - */ -#define __HAL_RCC_PLL_PLLSOURCE_CONFIG(__PLLSOURCE__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__PLLSOURCE__)) - -/** @brief Macro to configure the PLL multiplication factor. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * - */ -#define __HAL_RCC_PLL_PLLM_CONFIG(__PLLM__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, (__PLLM__)) -/** - * @} - */ - -/** @defgroup RCC_Get_Clock_source Get Clock source - * @{ - */ -/** - * @brief Macro to configure the system clock source. - * @param __RCC_SYSCLKSOURCE__ specifies the system clock source. - * This parameter can be one of the following values: - * - RCC_SYSCLKSOURCE_HSI: HSI oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_HSE: HSE oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLCLK: PLL output is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLRCLK: PLLR output is used as system clock source. This - * parameter is available only for STM32F446xx devices. - */ -#define __HAL_RCC_SYSCLK_CONFIG(__RCC_SYSCLKSOURCE__) MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__RCC_SYSCLKSOURCE__)) - -/** @brief Macro to get the clock source used as system clock. - * @retval The clock source used as system clock. The returned value can be one - * of the following: - * - RCC_SYSCLKSOURCE_STATUS_HSI: HSI used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_HSE: HSE used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLCLK: PLL used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLRCLK: PLLR used as system clock. This parameter - * is available only for STM32F446xx devices. - */ -#define __HAL_RCC_GET_SYSCLK_SOURCE() (RCC->CFGR & RCC_CFGR_SWS) - -/** @brief Macro to get the oscillator used as PLL clock source. - * @retval The oscillator used as PLL clock source. The returned value can be one - * of the following: - * - RCC_PLLSOURCE_HSI: HSI oscillator is used as PLL clock source. - * - RCC_PLLSOURCE_HSE: HSE oscillator is used as PLL clock source. - */ -#define __HAL_RCC_GET_PLL_OSCSOURCE() ((uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC)) -/** - * @} - */ - -/** @defgroup RCCEx_MCOx_Clock_Config RCC Extended MCOx Clock Config - * @{ - */ - -/** @brief Macro to configure the MCO1 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - */ -#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), ((__MCOCLKSOURCE__) | (__MCODIV__))) - -/** @brief Macro to configure the MCO2 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices - * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - * @note For STM32F410Rx devices, to output I2SCLK clock on MCO2, you should have - * at least one of the SPI clocks enabled (SPI1, SPI2 or SPI5). - */ -#define __HAL_RCC_MCO2_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), ((__MCOCLKSOURCE__) | ((__MCODIV__) << 3U))); -/** - * @} - */ - -/** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management - * @brief macros to manage the specified RCC Flags and interrupts. - * @{ - */ - -/** @brief Enable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to enable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_ENABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS |= (__INTERRUPT__)) - -/** @brief Disable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to disable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_DISABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS &= (uint8_t)(~(__INTERRUPT__))) - -/** @brief Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16] - * bits to clear the selected interrupt pending bits. - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - */ -#define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE2_ADDRESS = (__INTERRUPT__)) - -/** @brief Check the RCC's interrupt has occurred or not. - * @param __INTERRUPT__ specifies the RCC interrupt source to check. - * This parameter can be one of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIR & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** @brief Set RMVF bit to clear the reset flags: RCC_FLAG_PINRST, RCC_FLAG_PORRST, - * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST and RCC_FLAG_LPWRRST. - */ -#define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF) - -/** @brief Check RCC flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready. - * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready. - * @arg RCC_FLAG_PLLRDY: Main PLL clock ready. - * @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready. - * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready. - * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready. - * @arg RCC_FLAG_BORRST: POR/PDR or BOR reset. - * @arg RCC_FLAG_PINRST: Pin reset. - * @arg RCC_FLAG_PORRST: POR/PDR reset. - * @arg RCC_FLAG_SFTRST: Software reset. - * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset. - * @arg RCC_FLAG_WWDGRST: Window Watchdog reset. - * @arg RCC_FLAG_LPWRRST: Low Power reset. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define RCC_FLAG_MASK ((uint8_t)0x1FU) -#define __HAL_RCC_GET_FLAG(__FLAG__) (((((((__FLAG__) >> 5U) == 1U)? RCC->CR :((((__FLAG__) >> 5U) == 2U) ? RCC->BDCR :((((__FLAG__) >> 5U) == 3U)? RCC->CSR :RCC->CIR))) & (1U << ((__FLAG__) & RCC_FLAG_MASK)))!= 0U)? 1U : 0U) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - /** @addtogroup RCC_Exported_Functions - * @{ - */ - -/** @addtogroup RCC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ******************************/ -HAL_StatusTypeDef HAL_RCC_DeInit(void); -HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency); -/** - * @} - */ - -/** @addtogroup RCC_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv); -void HAL_RCC_EnableCSS(void); -void HAL_RCC_DisableCSS(void); -uint32_t HAL_RCC_GetSysClockFreq(void); -uint32_t HAL_RCC_GetHCLKFreq(void); -uint32_t HAL_RCC_GetPCLK1Freq(void); -uint32_t HAL_RCC_GetPCLK2Freq(void); -void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency); - -/* CSS NMI IRQ handler */ -void HAL_RCC_NMI_IRQHandler(void); - -/* User Callbacks in non blocking mode (IT mode) */ -void HAL_RCC_CSSCallback(void); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCC_Private_Constants RCC Private Constants - * @{ - */ - -/** @defgroup RCC_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) -/* --- CR Register --- */ -/* Alias word address of HSION bit */ -#define RCC_CR_OFFSET (RCC_OFFSET + 0x00U) -#define RCC_HSION_BIT_NUMBER 0x00U -#define RCC_CR_HSION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_HSION_BIT_NUMBER * 4U)) -/* Alias word address of CSSON bit */ -#define RCC_CSSON_BIT_NUMBER 0x13U -#define RCC_CR_CSSON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_CSSON_BIT_NUMBER * 4U)) -/* Alias word address of PLLON bit */ -#define RCC_PLLON_BIT_NUMBER 0x18U -#define RCC_CR_PLLON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLON_BIT_NUMBER * 4U)) - -/* --- BDCR Register --- */ -/* Alias word address of RTCEN bit */ -#define RCC_BDCR_OFFSET (RCC_OFFSET + 0x70U) -#define RCC_RTCEN_BIT_NUMBER 0x0FU -#define RCC_BDCR_RTCEN_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_RTCEN_BIT_NUMBER * 4U)) -/* Alias word address of BDRST bit */ -#define RCC_BDRST_BIT_NUMBER 0x10U -#define RCC_BDCR_BDRST_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_BDRST_BIT_NUMBER * 4U)) - -/* --- CSR Register --- */ -/* Alias word address of LSION bit */ -#define RCC_CSR_OFFSET (RCC_OFFSET + 0x74U) -#define RCC_LSION_BIT_NUMBER 0x00U -#define RCC_CSR_LSION_BB (PERIPH_BB_BASE + (RCC_CSR_OFFSET * 32U) + (RCC_LSION_BIT_NUMBER * 4U)) - -/* CR register byte 3 (Bits[23:16]) base address */ -#define RCC_CR_BYTE2_ADDRESS 0x40023802U - -/* CIR register byte 2 (Bits[15:8]) base address */ -#define RCC_CIR_BYTE1_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x01U)) - -/* CIR register byte 3 (Bits[23:16]) base address */ -#define RCC_CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x02U)) - -/* BDCR register base address */ -#define RCC_BDCR_BYTE0_ADDRESS (PERIPH_BASE + RCC_BDCR_OFFSET) - -#define RCC_DBP_TIMEOUT_VALUE 2U -#define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT - -#define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT -#define HSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define LSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define CLOCKSWITCH_TIMEOUT_VALUE 5000U /* 5 s */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCC_Private_Macros RCC Private Macros - * @{ - */ - -/** @defgroup RCC_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) ((OSCILLATOR) <= 15U) - -#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ - ((HSE) == RCC_HSE_BYPASS)) - -#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ - ((LSE) == RCC_LSE_BYPASS)) - -#define IS_RCC_HSI(HSI) (((HSI) == RCC_HSI_OFF) || ((HSI) == RCC_HSI_ON)) - -#define IS_RCC_LSI(LSI) (((LSI) == RCC_LSI_OFF) || ((LSI) == RCC_LSI_ON)) - -#define IS_RCC_PLL(PLL) (((PLL) == RCC_PLL_NONE) ||((PLL) == RCC_PLL_OFF) || ((PLL) == RCC_PLL_ON)) - -#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \ - ((SOURCE) == RCC_PLLSOURCE_HSE)) - -#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLRCLK)) - -#define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV2) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV3) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV4) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV5) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV6) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV7) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV8) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV9) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV10) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV11) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV12) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV13) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV14) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV15) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV16) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV17) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV18) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV19) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV20) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV21) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV22) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV23) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV24) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV25) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV26) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV27) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV28) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV29) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV30) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV31)) - -#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2U) || ((VALUE) == 4U) || ((VALUE) == 6U) || ((VALUE) == 8U)) - -#define IS_RCC_PLLQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_DIV1) || ((HCLK) == RCC_SYSCLK_DIV2) || \ - ((HCLK) == RCC_SYSCLK_DIV4) || ((HCLK) == RCC_SYSCLK_DIV8) || \ - ((HCLK) == RCC_SYSCLK_DIV16) || ((HCLK) == RCC_SYSCLK_DIV64) || \ - ((HCLK) == RCC_SYSCLK_DIV128) || ((HCLK) == RCC_SYSCLK_DIV256) || \ - ((HCLK) == RCC_SYSCLK_DIV512)) - -#define IS_RCC_CLOCKTYPE(CLK) ((1U <= (CLK)) && ((CLK) <= 15U)) - -#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_DIV1) || ((PCLK) == RCC_HCLK_DIV2) || \ - ((PCLK) == RCC_HCLK_DIV4) || ((PCLK) == RCC_HCLK_DIV8) || \ - ((PCLK) == RCC_HCLK_DIV16)) - -#define IS_RCC_MCO(MCOx) (((MCOx) == RCC_MCO1) || ((MCOx) == RCC_MCO2)) - -#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_HSI) || ((SOURCE) == RCC_MCO1SOURCE_LSE) || \ - ((SOURCE) == RCC_MCO1SOURCE_HSE) || ((SOURCE) == RCC_MCO1SOURCE_PLLCLK)) - -#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1) || ((DIV) == RCC_MCODIV_2) || \ - ((DIV) == RCC_MCODIV_3) || ((DIV) == RCC_MCODIV_4) || \ - ((DIV) == RCC_MCODIV_5)) -#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1FU) - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc.h + * @author MCD Application Team + * @brief Header file of RCC HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_RCC_H +#define __STM32F4xx_HAL_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/* Include RCC HAL Extended module */ +/* (include on top of file since RCC structures are defined in extended file) */ +#include "stm32f4xx_hal_rcc_ex.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup RCC_Exported_Types RCC Exported Types + * @{ + */ + +/** + * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition + */ +typedef struct +{ + uint32_t OscillatorType; /*!< The oscillators to be configured. + This parameter can be a value of @ref RCC_Oscillator_Type */ + + uint32_t HSEState; /*!< The new state of the HSE. + This parameter can be a value of @ref RCC_HSE_Config */ + + uint32_t LSEState; /*!< The new state of the LSE. + This parameter can be a value of @ref RCC_LSE_Config */ + + uint32_t HSIState; /*!< The new state of the HSI. + This parameter can be a value of @ref RCC_HSI_Config */ + + uint32_t HSICalibrationValue; /*!< The HSI calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT). + This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ + + uint32_t LSIState; /*!< The new state of the LSI. + This parameter can be a value of @ref RCC_LSI_Config */ + + RCC_PLLInitTypeDef PLL; /*!< PLL structure parameters */ +}RCC_OscInitTypeDef; + +/** + * @brief RCC System, AHB and APB busses clock configuration structure definition + */ +typedef struct +{ + uint32_t ClockType; /*!< The clock to be configured. + This parameter can be a value of @ref RCC_System_Clock_Type */ + + uint32_t SYSCLKSource; /*!< The clock source (SYSCLKS) used as system clock. + This parameter can be a value of @ref RCC_System_Clock_Source */ + + uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). + This parameter can be a value of @ref RCC_AHB_Clock_Source */ + + uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). + This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ + + uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). + This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ + +}RCC_ClkInitTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup RCC_Exported_Constants RCC Exported Constants + * @{ + */ + +/** @defgroup RCC_Oscillator_Type Oscillator Type + * @{ + */ +#define RCC_OSCILLATORTYPE_NONE 0x00000000U +#define RCC_OSCILLATORTYPE_HSE 0x00000001U +#define RCC_OSCILLATORTYPE_HSI 0x00000002U +#define RCC_OSCILLATORTYPE_LSE 0x00000004U +#define RCC_OSCILLATORTYPE_LSI 0x00000008U +/** + * @} + */ + +/** @defgroup RCC_HSE_Config HSE Config + * @{ + */ +#define RCC_HSE_OFF 0x00000000U +#define RCC_HSE_ON RCC_CR_HSEON +#define RCC_HSE_BYPASS ((uint32_t)(RCC_CR_HSEBYP | RCC_CR_HSEON)) +/** + * @} + */ + +/** @defgroup RCC_LSE_Config LSE Config + * @{ + */ +#define RCC_LSE_OFF 0x00000000U +#define RCC_LSE_ON RCC_BDCR_LSEON +#define RCC_LSE_BYPASS ((uint32_t)(RCC_BDCR_LSEBYP | RCC_BDCR_LSEON)) +/** + * @} + */ + +/** @defgroup RCC_HSI_Config HSI Config + * @{ + */ +#define RCC_HSI_OFF ((uint8_t)0x00) +#define RCC_HSI_ON ((uint8_t)0x01) + +#define RCC_HSICALIBRATION_DEFAULT 0x10U /* Default HSI calibration trimming value */ +/** + * @} + */ + +/** @defgroup RCC_LSI_Config LSI Config + * @{ + */ +#define RCC_LSI_OFF ((uint8_t)0x00) +#define RCC_LSI_ON ((uint8_t)0x01) +/** + * @} + */ + +/** @defgroup RCC_PLL_Config PLL Config + * @{ + */ +#define RCC_PLL_NONE ((uint8_t)0x00) +#define RCC_PLL_OFF ((uint8_t)0x01) +#define RCC_PLL_ON ((uint8_t)0x02) +/** + * @} + */ + +/** @defgroup RCC_PLLP_Clock_Divider PLLP Clock Divider + * @{ + */ +#define RCC_PLLP_DIV2 0x00000002U +#define RCC_PLLP_DIV4 0x00000004U +#define RCC_PLLP_DIV6 0x00000006U +#define RCC_PLLP_DIV8 0x00000008U +/** + * @} + */ + +/** @defgroup RCC_PLL_Clock_Source PLL Clock Source + * @{ + */ +#define RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI +#define RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE +/** + * @} + */ + +/** @defgroup RCC_System_Clock_Type System Clock Type + * @{ + */ +#define RCC_CLOCKTYPE_SYSCLK 0x00000001U +#define RCC_CLOCKTYPE_HCLK 0x00000002U +#define RCC_CLOCKTYPE_PCLK1 0x00000004U +#define RCC_CLOCKTYPE_PCLK2 0x00000008U +/** + * @} + */ + +/** @defgroup RCC_System_Clock_Source System Clock Source + * @note The RCC_SYSCLKSOURCE_PLLRCLK parameter is available only for + * STM32F446xx devices. + * @{ + */ +#define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI +#define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE +#define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL +#define RCC_SYSCLKSOURCE_PLLRCLK ((uint32_t)(RCC_CFGR_SW_0 | RCC_CFGR_SW_1)) +/** + * @} + */ + +/** @defgroup RCC_System_Clock_Source_Status System Clock Source Status + * @note The RCC_SYSCLKSOURCE_STATUS_PLLRCLK parameter is available only for + * STM32F446xx devices. + * @{ + */ +#define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ +#define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ +#define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ +#define RCC_SYSCLKSOURCE_STATUS_PLLRCLK ((uint32_t)(RCC_CFGR_SWS_0 | RCC_CFGR_SWS_1)) /*!< PLLR used as system clock */ +/** + * @} + */ + +/** @defgroup RCC_AHB_Clock_Source AHB Clock Source + * @{ + */ +#define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 +#define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 +#define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 +#define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 +#define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 +#define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 +#define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 +#define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 +#define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 +/** + * @} + */ + +/** @defgroup RCC_APB1_APB2_Clock_Source APB1/APB2 Clock Source + * @{ + */ +#define RCC_HCLK_DIV1 RCC_CFGR_PPRE1_DIV1 +#define RCC_HCLK_DIV2 RCC_CFGR_PPRE1_DIV2 +#define RCC_HCLK_DIV4 RCC_CFGR_PPRE1_DIV4 +#define RCC_HCLK_DIV8 RCC_CFGR_PPRE1_DIV8 +#define RCC_HCLK_DIV16 RCC_CFGR_PPRE1_DIV16 +/** + * @} + */ + +/** @defgroup RCC_RTC_Clock_Source RTC Clock Source + * @{ + */ +#define RCC_RTCCLKSOURCE_NO_CLK 0x00000000U +#define RCC_RTCCLKSOURCE_LSE 0x00000100U +#define RCC_RTCCLKSOURCE_LSI 0x00000200U +#define RCC_RTCCLKSOURCE_HSE_DIVX 0x00000300U +#define RCC_RTCCLKSOURCE_HSE_DIV2 0x00020300U +#define RCC_RTCCLKSOURCE_HSE_DIV3 0x00030300U +#define RCC_RTCCLKSOURCE_HSE_DIV4 0x00040300U +#define RCC_RTCCLKSOURCE_HSE_DIV5 0x00050300U +#define RCC_RTCCLKSOURCE_HSE_DIV6 0x00060300U +#define RCC_RTCCLKSOURCE_HSE_DIV7 0x00070300U +#define RCC_RTCCLKSOURCE_HSE_DIV8 0x00080300U +#define RCC_RTCCLKSOURCE_HSE_DIV9 0x00090300U +#define RCC_RTCCLKSOURCE_HSE_DIV10 0x000A0300U +#define RCC_RTCCLKSOURCE_HSE_DIV11 0x000B0300U +#define RCC_RTCCLKSOURCE_HSE_DIV12 0x000C0300U +#define RCC_RTCCLKSOURCE_HSE_DIV13 0x000D0300U +#define RCC_RTCCLKSOURCE_HSE_DIV14 0x000E0300U +#define RCC_RTCCLKSOURCE_HSE_DIV15 0x000F0300U +#define RCC_RTCCLKSOURCE_HSE_DIV16 0x00100300U +#define RCC_RTCCLKSOURCE_HSE_DIV17 0x00110300U +#define RCC_RTCCLKSOURCE_HSE_DIV18 0x00120300U +#define RCC_RTCCLKSOURCE_HSE_DIV19 0x00130300U +#define RCC_RTCCLKSOURCE_HSE_DIV20 0x00140300U +#define RCC_RTCCLKSOURCE_HSE_DIV21 0x00150300U +#define RCC_RTCCLKSOURCE_HSE_DIV22 0x00160300U +#define RCC_RTCCLKSOURCE_HSE_DIV23 0x00170300U +#define RCC_RTCCLKSOURCE_HSE_DIV24 0x00180300U +#define RCC_RTCCLKSOURCE_HSE_DIV25 0x00190300U +#define RCC_RTCCLKSOURCE_HSE_DIV26 0x001A0300U +#define RCC_RTCCLKSOURCE_HSE_DIV27 0x001B0300U +#define RCC_RTCCLKSOURCE_HSE_DIV28 0x001C0300U +#define RCC_RTCCLKSOURCE_HSE_DIV29 0x001D0300U +#define RCC_RTCCLKSOURCE_HSE_DIV30 0x001E0300U +#define RCC_RTCCLKSOURCE_HSE_DIV31 0x001F0300U +/** + * @} + */ + +/** @defgroup RCC_MCO_Index MCO Index + * @{ + */ +#define RCC_MCO1 0x00000000U +#define RCC_MCO2 0x00000001U +/** + * @} + */ + +/** @defgroup RCC_MCO1_Clock_Source MCO1 Clock Source + * @{ + */ +#define RCC_MCO1SOURCE_HSI 0x00000000U +#define RCC_MCO1SOURCE_LSE RCC_CFGR_MCO1_0 +#define RCC_MCO1SOURCE_HSE RCC_CFGR_MCO1_1 +#define RCC_MCO1SOURCE_PLLCLK RCC_CFGR_MCO1 +/** + * @} + */ + +/** @defgroup RCC_MCOx_Clock_Prescaler MCOx Clock Prescaler + * @{ + */ +#define RCC_MCODIV_1 0x00000000U +#define RCC_MCODIV_2 RCC_CFGR_MCO1PRE_2 +#define RCC_MCODIV_3 ((uint32_t)RCC_CFGR_MCO1PRE_0 | RCC_CFGR_MCO1PRE_2) +#define RCC_MCODIV_4 ((uint32_t)RCC_CFGR_MCO1PRE_1 | RCC_CFGR_MCO1PRE_2) +#define RCC_MCODIV_5 RCC_CFGR_MCO1PRE +/** + * @} + */ + +/** @defgroup RCC_Interrupt Interrupts + * @{ + */ +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_PLLI2SRDY ((uint8_t)0x20) +#define RCC_IT_CSS ((uint8_t)0x80) +/** + * @} + */ + +/** @defgroup RCC_Flag Flags + * Elements values convention: 0XXYYYYYb + * - YYYYY : Flag position in the register + * - 0XX : Register index + * - 01: CR register + * - 10: BDCR register + * - 11: CSR register + * @{ + */ +/* Flags in the CR register */ +#define RCC_FLAG_HSIRDY ((uint8_t)0x21) +#define RCC_FLAG_HSERDY ((uint8_t)0x31) +#define RCC_FLAG_PLLRDY ((uint8_t)0x39) +#define RCC_FLAG_PLLI2SRDY ((uint8_t)0x3B) + +/* Flags in the BDCR register */ +#define RCC_FLAG_LSERDY ((uint8_t)0x41) + +/* Flags in the CSR register */ +#define RCC_FLAG_LSIRDY ((uint8_t)0x61) +#define RCC_FLAG_BORRST ((uint8_t)0x79) +#define RCC_FLAG_PINRST ((uint8_t)0x7A) +#define RCC_FLAG_PORRST ((uint8_t)0x7B) +#define RCC_FLAG_SFTRST ((uint8_t)0x7C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup RCC_Exported_Macros RCC Exported Macros + * @{ + */ + +/** @defgroup RCC_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOA_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOB_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOH_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DMA1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DMA2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_GPIOA_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOAEN)) +#define __HAL_RCC_GPIOB_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOBEN)) +#define __HAL_RCC_GPIOC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOCEN)) +#define __HAL_RCC_GPIOH_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOHEN)) +#define __HAL_RCC_DMA1_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA1EN)) +#define __HAL_RCC_DMA2_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2EN)) +/** + * @} + */ + +/** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOA_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) != RESET) +#define __HAL_RCC_GPIOB_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) != RESET) +#define __HAL_RCC_GPIOC_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) != RESET) +#define __HAL_RCC_GPIOH_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) != RESET) +#define __HAL_RCC_DMA1_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) != RESET) +#define __HAL_RCC_DMA2_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) != RESET) + +#define __HAL_RCC_GPIOA_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) == RESET) +#define __HAL_RCC_GPIOB_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) == RESET) +#define __HAL_RCC_GPIOC_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) == RESET) +#define __HAL_RCC_GPIOH_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) == RESET) +#define __HAL_RCC_DMA1_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) == RESET) +#define __HAL_RCC_DMA2_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_WWDG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_PWR_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_TIM5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM5EN)) +#define __HAL_RCC_WWDG_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_WWDGEN)) +#define __HAL_RCC_SPI2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN)) +#define __HAL_RCC_USART2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART2EN)) +#define __HAL_RCC_I2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN)) +#define __HAL_RCC_I2C2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C2EN)) +#define __HAL_RCC_PWR_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_PWREN)) +/** + * @} + */ + +/** @defgroup RCC_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) != RESET) +#define __HAL_RCC_WWDG_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) != RESET) +#define __HAL_RCC_SPI2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) != RESET) +#define __HAL_RCC_USART2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) != RESET) +#define __HAL_RCC_I2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) != RESET) +#define __HAL_RCC_I2C2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) != RESET) +#define __HAL_RCC_PWR_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) != RESET) + +#define __HAL_RCC_TIM5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) == RESET) +#define __HAL_RCC_WWDG_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) == RESET) +#define __HAL_RCC_SPI2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) == RESET) +#define __HAL_RCC_USART2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) == RESET) +#define __HAL_RCC_I2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) == RESET) +#define __HAL_RCC_I2C2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) == RESET) +#define __HAL_RCC_PWR_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) == RESET) +/** + * @} + */ + +/** @defgroup RCC_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM9_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM11_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_TIM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM1EN)) +#define __HAL_RCC_USART1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN)) +#define __HAL_RCC_USART6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART6EN)) +#define __HAL_RCC_ADC1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN)) +#define __HAL_RCC_SPI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN)) +#define __HAL_RCC_SYSCFG_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SYSCFGEN)) +#define __HAL_RCC_TIM9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM9EN)) +#define __HAL_RCC_TIM11_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM11EN)) +/** + * @} + */ + +/** @defgroup RCC_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) != RESET) +#define __HAL_RCC_USART1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) != RESET) +#define __HAL_RCC_USART6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) != RESET) +#define __HAL_RCC_ADC1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) != RESET) +#define __HAL_RCC_SPI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) != RESET) +#define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) != RESET) +#define __HAL_RCC_TIM9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) != RESET) +#define __HAL_RCC_TIM11_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) != RESET) + +#define __HAL_RCC_TIM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) == RESET) +#define __HAL_RCC_USART1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) == RESET) +#define __HAL_RCC_USART6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) == RESET) +#define __HAL_RCC_ADC1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) == RESET) +#define __HAL_RCC_SPI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) == RESET) +#define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) == RESET) +#define __HAL_RCC_TIM9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) == RESET) +#define __HAL_RCC_TIM11_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCC_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_GPIOA_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOARST)) +#define __HAL_RCC_GPIOB_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOBRST)) +#define __HAL_RCC_GPIOC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOCRST)) +#define __HAL_RCC_GPIOH_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOHRST)) +#define __HAL_RCC_DMA1_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA1RST)) +#define __HAL_RCC_DMA2_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2RST)) + +#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) +#define __HAL_RCC_GPIOA_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOARST)) +#define __HAL_RCC_GPIOB_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOBRST)) +#define __HAL_RCC_GPIOC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOCRST)) +#define __HAL_RCC_GPIOH_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOHRST)) +#define __HAL_RCC_DMA1_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA1RST)) +#define __HAL_RCC_DMA2_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2RST)) +/** + * @} + */ + +/** @defgroup RCC_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_TIM5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM5RST)) +#define __HAL_RCC_WWDG_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_WWDGRST)) +#define __HAL_RCC_SPI2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI2RST)) +#define __HAL_RCC_USART2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART2RST)) +#define __HAL_RCC_I2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C1RST)) +#define __HAL_RCC_I2C2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C2RST)) +#define __HAL_RCC_PWR_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_PWRRST)) + +#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) +#define __HAL_RCC_TIM5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM5RST)) +#define __HAL_RCC_WWDG_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_WWDGRST)) +#define __HAL_RCC_SPI2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI2RST)) +#define __HAL_RCC_USART2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART2RST)) +#define __HAL_RCC_I2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C1RST)) +#define __HAL_RCC_I2C2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C2RST)) +#define __HAL_RCC_PWR_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_PWRRST)) +/** + * @} + */ + +/** @defgroup RCC_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_TIM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM1RST)) +#define __HAL_RCC_USART1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART1RST)) +#define __HAL_RCC_USART6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART6RST)) +#define __HAL_RCC_ADC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_ADCRST)) +#define __HAL_RCC_SPI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI1RST)) +#define __HAL_RCC_SYSCFG_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SYSCFGRST)) +#define __HAL_RCC_TIM9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM9RST)) +#define __HAL_RCC_TIM11_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM11RST)) + +#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) +#define __HAL_RCC_TIM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM1RST)) +#define __HAL_RCC_USART1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART1RST)) +#define __HAL_RCC_USART6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART6RST)) +#define __HAL_RCC_ADC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_ADCRST)) +#define __HAL_RCC_SPI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI1RST)) +#define __HAL_RCC_SYSCFG_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SYSCFGRST)) +#define __HAL_RCC_TIM9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM9RST)) +#define __HAL_RCC_TIM11_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM11RST)) +/** + * @} + */ + +/** @defgroup RCC_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOALPEN)) +#define __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOBLPEN)) +#define __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOCLPEN)) +#define __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOHLPEN)) +#define __HAL_RCC_DMA1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA1LPEN)) +#define __HAL_RCC_DMA2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2LPEN)) + +#define __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOALPEN)) +#define __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOBLPEN)) +#define __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOCLPEN)) +#define __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOHLPEN)) +#define __HAL_RCC_DMA1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA1LPEN)) +#define __HAL_RCC_DMA2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2LPEN)) +/** + * @} + */ + +/** @defgroup RCC_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM5LPEN)) +#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_WWDGLPEN)) +#define __HAL_RCC_SPI2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI2LPEN)) +#define __HAL_RCC_USART2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART2LPEN)) +#define __HAL_RCC_I2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C1LPEN)) +#define __HAL_RCC_I2C2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C2LPEN)) +#define __HAL_RCC_PWR_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_PWRLPEN)) + +#define __HAL_RCC_TIM5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM5LPEN)) +#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_WWDGLPEN)) +#define __HAL_RCC_SPI2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI2LPEN)) +#define __HAL_RCC_USART2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART2LPEN)) +#define __HAL_RCC_I2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C1LPEN)) +#define __HAL_RCC_I2C2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C2LPEN)) +#define __HAL_RCC_PWR_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_PWRLPEN)) +/** + * @} + */ + +/** @defgroup RCC_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM1LPEN)) +#define __HAL_RCC_USART1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART1LPEN)) +#define __HAL_RCC_USART6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART6LPEN)) +#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC1LPEN)) +#define __HAL_RCC_SPI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI1LPEN)) +#define __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SYSCFGLPEN)) +#define __HAL_RCC_TIM9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM9LPEN)) +#define __HAL_RCC_TIM11_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM11LPEN)) + +#define __HAL_RCC_TIM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM1LPEN)) +#define __HAL_RCC_USART1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART1LPEN)) +#define __HAL_RCC_USART6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART6LPEN)) +#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC1LPEN)) +#define __HAL_RCC_SPI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI1LPEN)) +#define __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SYSCFGLPEN)) +#define __HAL_RCC_TIM9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM9LPEN)) +#define __HAL_RCC_TIM11_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM11LPEN)) +/** + * @} + */ + +/** @defgroup RCC_HSI_Configuration HSI Configuration + * @{ + */ + +/** @brief Macros to enable or disable the Internal High Speed oscillator (HSI). + * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. + * It is used (enabled by hardware) as system clock source after startup + * from Reset, wake-up from STOP and STANDBY mode, or in case of failure + * of the HSE used directly or indirectly as system clock (if the Clock + * Security System CSS is enabled). + * @note HSI can not be stopped if it is used as system clock source. In this case, + * you have to select another source of the system clock then stop the HSI. + * @note After enabling the HSI, the application software should wait on HSIRDY + * flag to be set indicating that HSI clock is stable and can be used as + * system clock source. + * This parameter can be: ENABLE or DISABLE. + * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator + * clock cycles. + */ +#define __HAL_RCC_HSI_ENABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = ENABLE) +#define __HAL_RCC_HSI_DISABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = DISABLE) + +/** @brief Macro to adjust the Internal High Speed oscillator (HSI) calibration value. + * @note The calibration is used to compensate for the variations in voltage + * and temperature that influence the frequency of the internal HSI RC. + * @param __HSICalibrationValue__ specifies the calibration trimming value. + * (default is RCC_HSICALIBRATION_DEFAULT). + * This parameter must be a number between 0 and 0x1F. + */ +#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICalibrationValue__) (MODIFY_REG(RCC->CR,\ + RCC_CR_HSITRIM, (uint32_t)(__HSICalibrationValue__) << RCC_CR_HSITRIM_Pos)) +/** + * @} + */ + +/** @defgroup RCC_LSI_Configuration LSI Configuration + * @{ + */ + +/** @brief Macros to enable or disable the Internal Low Speed oscillator (LSI). + * @note After enabling the LSI, the application software should wait on + * LSIRDY flag to be set indicating that LSI clock is stable and can + * be used to clock the IWDG and/or the RTC. + * @note LSI can not be disabled if the IWDG is running. + * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator + * clock cycles. + */ +#define __HAL_RCC_LSI_ENABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = ENABLE) +#define __HAL_RCC_LSI_DISABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = DISABLE) +/** + * @} + */ + +/** @defgroup RCC_HSE_Configuration HSE Configuration + * @{ + */ + +/** + * @brief Macro to configure the External High Speed oscillator (HSE). + * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not supported by this macro. + * User should request a transition to HSE Off first and then HSE On or HSE Bypass. + * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application + * software should wait on HSERDY flag to be set indicating that HSE clock + * is stable and can be used to clock the PLL and/or system clock. + * @note HSE state can not be changed if it is used directly or through the + * PLL as system clock. In this case, you have to select another source + * of the system clock then change the HSE state (ex. disable it). + * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. + * @note This function reset the CSSON bit, so if the clock security system(CSS) + * was previously enabled you have to enable it again after calling this + * function. + * @param __STATE__ specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after + * 6 HSE oscillator clock cycles. + * @arg RCC_HSE_ON: turn ON the HSE oscillator. + * @arg RCC_HSE_BYPASS: HSE oscillator bypassed with external clock. + */ +#define __HAL_RCC_HSE_CONFIG(__STATE__) \ + do { \ + if ((__STATE__) == RCC_HSE_ON) \ + { \ + SET_BIT(RCC->CR, RCC_CR_HSEON); \ + } \ + else if ((__STATE__) == RCC_HSE_BYPASS) \ + { \ + SET_BIT(RCC->CR, RCC_CR_HSEBYP); \ + SET_BIT(RCC->CR, RCC_CR_HSEON); \ + } \ + else \ + { \ + CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \ + CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \ + } \ + } while(0U) +/** + * @} + */ + +/** @defgroup RCC_LSE_Configuration LSE Configuration + * @{ + */ + +/** + * @brief Macro to configure the External Low Speed oscillator (LSE). + * @note Transition LSE Bypass to LSE On and LSE On to LSE Bypass are not supported by this macro. + * User should request a transition to LSE Off first and then LSE On or LSE Bypass. + * @note As the LSE is in the Backup domain and write access is denied to + * this domain after reset, you have to enable write access using + * HAL_PWR_EnableBkUpAccess() function before to configure the LSE + * (to be done once after reset). + * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application + * software should wait on LSERDY flag to be set indicating that LSE clock + * is stable and can be used to clock the RTC. + * @param __STATE__ specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after + * 6 LSE oscillator clock cycles. + * @arg RCC_LSE_ON: turn ON the LSE oscillator. + * @arg RCC_LSE_BYPASS: LSE oscillator bypassed with external clock. + */ +#define __HAL_RCC_LSE_CONFIG(__STATE__) \ + do { \ + if((__STATE__) == RCC_LSE_ON) \ + { \ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ + } \ + else if((__STATE__) == RCC_LSE_BYPASS) \ + { \ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ + } \ + else \ + { \ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ + } \ + } while(0U) +/** + * @} + */ + +/** @defgroup RCC_Internal_RTC_Clock_Configuration RTC Clock Configuration + * @{ + */ + +/** @brief Macros to enable or disable the RTC clock. + * @note These macros must be used only after the RTC clock source was selected. + */ +#define __HAL_RCC_RTC_ENABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = ENABLE) +#define __HAL_RCC_RTC_DISABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = DISABLE) + +/** @brief Macros to configure the RTC clock (RTCCLK). + * @note As the RTC clock configuration bits are in the Backup domain and write + * access is denied to this domain after reset, you have to enable write + * access using the Power Backup Access macro before to configure + * the RTC clock source (to be done once after reset). + * @note Once the RTC clock is configured it can't be changed unless the + * Backup domain is reset using __HAL_RCC_BackupReset_RELEASE() macro, or by + * a Power On Reset (POR). + * @param __RTCCLKSource__ specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg @ref RCC_RTCCLKSOURCE_NO_CLK : No clock selected as RTC clock. + * @arg @ref RCC_RTCCLKSOURCE_LSE : LSE selected as RTC clock. + * @arg @ref RCC_RTCCLKSOURCE_LSI : LSI selected as RTC clock. + * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() + * @note If the LSE or LSI is used as RTC clock source, the RTC continues to + * work in STOP and STANDBY modes, and can be used as wake-up source. + * However, when the HSE clock is used as RTC clock source, the RTC + * cannot be used in STOP and STANDBY modes. + * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as + * RTC clock source). + */ +#define __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__) (((__RTCCLKSource__) & RCC_BDCR_RTCSEL) == RCC_BDCR_RTCSEL) ? \ + MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, ((__RTCCLKSource__) & 0xFFFFCFFU)) : CLEAR_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) + +#define __HAL_RCC_RTC_CONFIG(__RTCCLKSource__) do { __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__); \ + RCC->BDCR |= ((__RTCCLKSource__) & 0x00000FFFU); \ + } while(0U) + +/** @brief Macro to get the RTC clock source. + * @retval The clock source can be one of the following values: + * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock + * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock + * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock + * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() + */ +#define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)) + +/** + * @brief Get the RTC and HSE clock divider (RTCPRE). + * @retval Returned value can be one of the following values: + * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() + */ +#define __HAL_RCC_GET_RTC_HSE_PRESCALER() (READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) | RCC_BDCR_RTCSEL) + +/** @brief Macros to force or release the Backup domain reset. + * @note This function resets the RTC peripheral (including the backup registers) + * and the RTC clock source selection in RCC_CSR register. + * @note The BKPSRAM is not affected by this reset. + */ +#define __HAL_RCC_BACKUPRESET_FORCE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = ENABLE) +#define __HAL_RCC_BACKUPRESET_RELEASE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = DISABLE) +/** + * @} + */ + +/** @defgroup RCC_PLL_Configuration PLL Configuration + * @{ + */ + +/** @brief Macros to enable or disable the main PLL. + * @note After enabling the main PLL, the application software should wait on + * PLLRDY flag to be set indicating that PLL clock is stable and can + * be used as system clock source. + * @note The main PLL can not be disabled if it is used as system clock source + * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes. + */ +#define __HAL_RCC_PLL_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = ENABLE) +#define __HAL_RCC_PLL_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = DISABLE) + +/** @brief Macro to configure the PLL clock source. + * @note This function must be used only when the main PLL is disabled. + * @param __PLLSOURCE__ specifies the PLL entry clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry + * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry + * + */ +#define __HAL_RCC_PLL_PLLSOURCE_CONFIG(__PLLSOURCE__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__PLLSOURCE__)) + +/** @brief Macro to configure the PLL multiplication factor. + * @note This function must be used only when the main PLL is disabled. + * @param __PLLM__ specifies the division factor for PLL VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 2 MHz to limit PLL jitter. + * + */ +#define __HAL_RCC_PLL_PLLM_CONFIG(__PLLM__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, (__PLLM__)) +/** + * @} + */ + +/** @defgroup RCC_Get_Clock_source Get Clock source + * @{ + */ +/** + * @brief Macro to configure the system clock source. + * @param __RCC_SYSCLKSOURCE__ specifies the system clock source. + * This parameter can be one of the following values: + * - RCC_SYSCLKSOURCE_HSI: HSI oscillator is used as system clock source. + * - RCC_SYSCLKSOURCE_HSE: HSE oscillator is used as system clock source. + * - RCC_SYSCLKSOURCE_PLLCLK: PLL output is used as system clock source. + * - RCC_SYSCLKSOURCE_PLLRCLK: PLLR output is used as system clock source. This + * parameter is available only for STM32F446xx devices. + */ +#define __HAL_RCC_SYSCLK_CONFIG(__RCC_SYSCLKSOURCE__) MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__RCC_SYSCLKSOURCE__)) + +/** @brief Macro to get the clock source used as system clock. + * @retval The clock source used as system clock. The returned value can be one + * of the following: + * - RCC_SYSCLKSOURCE_STATUS_HSI: HSI used as system clock. + * - RCC_SYSCLKSOURCE_STATUS_HSE: HSE used as system clock. + * - RCC_SYSCLKSOURCE_STATUS_PLLCLK: PLL used as system clock. + * - RCC_SYSCLKSOURCE_STATUS_PLLRCLK: PLLR used as system clock. This parameter + * is available only for STM32F446xx devices. + */ +#define __HAL_RCC_GET_SYSCLK_SOURCE() (RCC->CFGR & RCC_CFGR_SWS) + +/** @brief Macro to get the oscillator used as PLL clock source. + * @retval The oscillator used as PLL clock source. The returned value can be one + * of the following: + * - RCC_PLLSOURCE_HSI: HSI oscillator is used as PLL clock source. + * - RCC_PLLSOURCE_HSE: HSE oscillator is used as PLL clock source. + */ +#define __HAL_RCC_GET_PLL_OSCSOURCE() ((uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC)) +/** + * @} + */ + +/** @defgroup RCCEx_MCOx_Clock_Config RCC Extended MCOx Clock Config + * @{ + */ + +/** @brief Macro to configure the MCO1 clock. + * @param __MCOCLKSOURCE__ specifies the MCO clock source. + * This parameter can be one of the following values: + * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source + * @param __MCODIV__ specifies the MCO clock prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCODIV_1: no division applied to MCOx clock + * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock + * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock + * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock + * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock + */ +#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), ((__MCOCLKSOURCE__) | (__MCODIV__))) + +/** @brief Macro to configure the MCO2 clock. + * @param __MCOCLKSOURCE__ specifies the MCO clock source. + * This parameter can be one of the following values: + * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx + * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices + * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source + * @param __MCODIV__ specifies the MCO clock prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCODIV_1: no division applied to MCOx clock + * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock + * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock + * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock + * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock + * @note For STM32F410Rx devices, to output I2SCLK clock on MCO2, you should have + * at least one of the SPI clocks enabled (SPI1, SPI2 or SPI5). + */ +#define __HAL_RCC_MCO2_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), ((__MCOCLKSOURCE__) | ((__MCODIV__) << 3U))); +/** + * @} + */ + +/** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management + * @brief macros to manage the specified RCC Flags and interrupts. + * @{ + */ + +/** @brief Enable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to enable + * the selected interrupts). + * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt. + * @arg RCC_IT_LSERDY: LSE ready interrupt. + * @arg RCC_IT_HSIRDY: HSI ready interrupt. + * @arg RCC_IT_HSERDY: HSE ready interrupt. + * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. + */ +#define __HAL_RCC_ENABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS |= (__INTERRUPT__)) + +/** @brief Disable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to disable + * the selected interrupts). + * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt. + * @arg RCC_IT_LSERDY: LSE ready interrupt. + * @arg RCC_IT_HSIRDY: HSI ready interrupt. + * @arg RCC_IT_HSERDY: HSE ready interrupt. + * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. + */ +#define __HAL_RCC_DISABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS &= (uint8_t)(~(__INTERRUPT__))) + +/** @brief Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16] + * bits to clear the selected interrupt pending bits. + * @param __INTERRUPT__ specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt. + * @arg RCC_IT_LSERDY: LSE ready interrupt. + * @arg RCC_IT_HSIRDY: HSI ready interrupt. + * @arg RCC_IT_HSERDY: HSE ready interrupt. + * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. + * @arg RCC_IT_CSS: Clock Security System interrupt + */ +#define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE2_ADDRESS = (__INTERRUPT__)) + +/** @brief Check the RCC's interrupt has occurred or not. + * @param __INTERRUPT__ specifies the RCC interrupt source to check. + * This parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt. + * @arg RCC_IT_LSERDY: LSE ready interrupt. + * @arg RCC_IT_HSIRDY: HSI ready interrupt. + * @arg RCC_IT_HSERDY: HSE ready interrupt. + * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval The new state of __INTERRUPT__ (TRUE or FALSE). + */ +#define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIR & (__INTERRUPT__)) == (__INTERRUPT__)) + +/** @brief Set RMVF bit to clear the reset flags: RCC_FLAG_PINRST, RCC_FLAG_PORRST, + * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST and RCC_FLAG_LPWRRST. + */ +#define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF) + +/** @brief Check RCC flag is set or not. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready. + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready. + * @arg RCC_FLAG_PLLRDY: Main PLL clock ready. + * @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready. + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready. + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready. + * @arg RCC_FLAG_BORRST: POR/PDR or BOR reset. + * @arg RCC_FLAG_PINRST: Pin reset. + * @arg RCC_FLAG_PORRST: POR/PDR reset. + * @arg RCC_FLAG_SFTRST: Software reset. + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset. + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset. + * @arg RCC_FLAG_LPWRRST: Low Power reset. + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define RCC_FLAG_MASK ((uint8_t)0x1FU) +#define __HAL_RCC_GET_FLAG(__FLAG__) (((((((__FLAG__) >> 5U) == 1U)? RCC->CR :((((__FLAG__) >> 5U) == 2U) ? RCC->BDCR :((((__FLAG__) >> 5U) == 3U)? RCC->CSR :RCC->CIR))) & (1U << ((__FLAG__) & RCC_FLAG_MASK)))!= 0U)? 1U : 0U) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + /** @addtogroup RCC_Exported_Functions + * @{ + */ + +/** @addtogroup RCC_Exported_Functions_Group1 + * @{ + */ +/* Initialization and de-initialization functions ******************************/ +HAL_StatusTypeDef HAL_RCC_DeInit(void); +HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); +HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency); +/** + * @} + */ + +/** @addtogroup RCC_Exported_Functions_Group2 + * @{ + */ +/* Peripheral Control functions ************************************************/ +void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv); +void HAL_RCC_EnableCSS(void); +void HAL_RCC_DisableCSS(void); +uint32_t HAL_RCC_GetSysClockFreq(void); +uint32_t HAL_RCC_GetHCLKFreq(void); +uint32_t HAL_RCC_GetPCLK1Freq(void); +uint32_t HAL_RCC_GetPCLK2Freq(void); +void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); +void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency); + +/* CSS NMI IRQ handler */ +void HAL_RCC_NMI_IRQHandler(void); + +/* User Callbacks in non blocking mode (IT mode) */ +void HAL_RCC_CSSCallback(void); + +/** + * @} + */ + +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup RCC_Private_Constants RCC Private Constants + * @{ + */ + +/** @defgroup RCC_BitAddress_AliasRegion RCC BitAddress AliasRegion + * @brief RCC registers bit address in the alias region + * @{ + */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) +/* --- CR Register --- */ +/* Alias word address of HSION bit */ +#define RCC_CR_OFFSET (RCC_OFFSET + 0x00U) +#define RCC_HSION_BIT_NUMBER 0x00U +#define RCC_CR_HSION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_HSION_BIT_NUMBER * 4U)) +/* Alias word address of CSSON bit */ +#define RCC_CSSON_BIT_NUMBER 0x13U +#define RCC_CR_CSSON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_CSSON_BIT_NUMBER * 4U)) +/* Alias word address of PLLON bit */ +#define RCC_PLLON_BIT_NUMBER 0x18U +#define RCC_CR_PLLON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLON_BIT_NUMBER * 4U)) + +/* --- BDCR Register --- */ +/* Alias word address of RTCEN bit */ +#define RCC_BDCR_OFFSET (RCC_OFFSET + 0x70U) +#define RCC_RTCEN_BIT_NUMBER 0x0FU +#define RCC_BDCR_RTCEN_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_RTCEN_BIT_NUMBER * 4U)) +/* Alias word address of BDRST bit */ +#define RCC_BDRST_BIT_NUMBER 0x10U +#define RCC_BDCR_BDRST_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_BDRST_BIT_NUMBER * 4U)) + +/* --- CSR Register --- */ +/* Alias word address of LSION bit */ +#define RCC_CSR_OFFSET (RCC_OFFSET + 0x74U) +#define RCC_LSION_BIT_NUMBER 0x00U +#define RCC_CSR_LSION_BB (PERIPH_BB_BASE + (RCC_CSR_OFFSET * 32U) + (RCC_LSION_BIT_NUMBER * 4U)) + +/* CR register byte 3 (Bits[23:16]) base address */ +#define RCC_CR_BYTE2_ADDRESS 0x40023802U + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define RCC_CIR_BYTE1_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x01U)) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define RCC_CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x02U)) + +/* BDCR register base address */ +#define RCC_BDCR_BYTE0_ADDRESS (PERIPH_BASE + RCC_BDCR_OFFSET) + +#define RCC_DBP_TIMEOUT_VALUE 2U +#define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT + +#define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT +#define HSI_TIMEOUT_VALUE 2U /* 2 ms */ +#define LSI_TIMEOUT_VALUE 2U /* 2 ms */ +#define CLOCKSWITCH_TIMEOUT_VALUE 5000U /* 5 s */ + +/** + * @} + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup RCC_Private_Macros RCC Private Macros + * @{ + */ + +/** @defgroup RCC_IS_RCC_Definitions RCC Private macros to check input parameters + * @{ + */ +#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) ((OSCILLATOR) <= 15U) + +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_BYPASS)) + +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_BYPASS)) + +#define IS_RCC_HSI(HSI) (((HSI) == RCC_HSI_OFF) || ((HSI) == RCC_HSI_ON)) + +#define IS_RCC_LSI(LSI) (((LSI) == RCC_LSI_OFF) || ((LSI) == RCC_LSI_ON)) + +#define IS_RCC_PLL(PLL) (((PLL) == RCC_PLL_NONE) ||((PLL) == RCC_PLL_OFF) || ((PLL) == RCC_PLL_ON)) + +#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \ + ((SOURCE) == RCC_PLLSOURCE_HSE)) + +#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \ + ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \ + ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK) || \ + ((SOURCE) == RCC_SYSCLKSOURCE_PLLRCLK)) + +#define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV2) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV3) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV4) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV5) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV6) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV7) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV8) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV9) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV10) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV11) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV12) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV13) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV14) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV15) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV16) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV17) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV18) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV19) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV20) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV21) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV22) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV23) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV24) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV25) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV26) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV27) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV28) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV29) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV30) || \ + ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV31)) + +#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63U) + +#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2U) || ((VALUE) == 4U) || ((VALUE) == 6U) || ((VALUE) == 8U)) + +#define IS_RCC_PLLQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) + +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_DIV1) || ((HCLK) == RCC_SYSCLK_DIV2) || \ + ((HCLK) == RCC_SYSCLK_DIV4) || ((HCLK) == RCC_SYSCLK_DIV8) || \ + ((HCLK) == RCC_SYSCLK_DIV16) || ((HCLK) == RCC_SYSCLK_DIV64) || \ + ((HCLK) == RCC_SYSCLK_DIV128) || ((HCLK) == RCC_SYSCLK_DIV256) || \ + ((HCLK) == RCC_SYSCLK_DIV512)) + +#define IS_RCC_CLOCKTYPE(CLK) ((1U <= (CLK)) && ((CLK) <= 15U)) + +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_DIV1) || ((PCLK) == RCC_HCLK_DIV2) || \ + ((PCLK) == RCC_HCLK_DIV4) || ((PCLK) == RCC_HCLK_DIV8) || \ + ((PCLK) == RCC_HCLK_DIV16)) + +#define IS_RCC_MCO(MCOx) (((MCOx) == RCC_MCO1) || ((MCOx) == RCC_MCO2)) + +#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_HSI) || ((SOURCE) == RCC_MCO1SOURCE_LSE) || \ + ((SOURCE) == RCC_MCO1SOURCE_HSE) || ((SOURCE) == RCC_MCO1SOURCE_PLLCLK)) + +#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1) || ((DIV) == RCC_MCODIV_2) || \ + ((DIV) == RCC_MCODIV_3) || ((DIV) == RCC_MCODIV_4) || \ + ((DIV) == RCC_MCODIV_5)) +#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1FU) + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_RCC_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h index 909a717..1ac56e1 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h @@ -1,7111 +1,7111 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc_ex.h - * @author MCD Application Team - * @brief Header file of RCC HAL Extension module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_EX_H -#define __STM32F4xx_HAL_RCC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Types RCCEx Exported Types - * @{ - */ - -/** - * @brief RCC PLL configuration structure definition - */ -typedef struct -{ - uint32_t PLLState; /*!< The new state of the PLL. - This parameter can be a value of @ref RCC_PLL_Config */ - - uint32_t PLLSource; /*!< RCC_PLLSource: PLL entry clock source. - This parameter must be a value of @ref RCC_PLL_Clock_Source */ - - uint32_t PLLM; /*!< PLLM: Division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 0 and Max_Data = 63 */ - - uint32_t PLLN; /*!< PLLN: Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - except for STM32F411xE devices where the Min_Data = 192 */ - - uint32_t PLLP; /*!< PLLP: Division factor for main system clock (SYSCLK). - This parameter must be a value of @ref RCC_PLLP_Clock_Divider */ - - uint32_t PLLQ; /*!< PLLQ: Division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a number between Min_Data = 2 and Max_Data = 15 */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLR; /*!< PLLR: PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - This parameter is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx - and STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - This parameter must be a number between Min_Data = 2 and Max_Data = 7 */ -#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -}RCC_PLLInitTypeDef; - -#if defined(STM32F446xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SP; /*!< Specifies division factor for SPDIFRX Clock. - This parameter must be a value of @ref RCCEx_PLLI2SP_Clock_Divider */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t Sai1ClockSelection; /*!< Specifies SAI1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI1_Clock_Source */ - - uint32_t Sai2ClockSelection; /*!< Specifies SAI2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI2_Clock_Source */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t CecClockSelection; /*!< Specifies CEC Clock Source Selection. - This parameter can be a value of @ref RCCEx_CEC_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t SpdifClockSelection; /*!< Specifies SPDIFRX Clock Source Selection. - This parameter can be a value of @ref RCCEx_SPDIFRX_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F446xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - uint32_t I2SClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2S_APB_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLDivR; /*!< Specifies the PLL division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLL is selected as Clock Source SAI */ - - uint32_t PLLI2SDivR; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t Dfsdm1ClockSelection; /*!< Specifies DFSDM1 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Kernel_Clock_Source */ - - uint32_t Dfsdm1AudioClockSelection;/*!< Specifies DFSDM1 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Audio_Clock_Source */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t Dfsdm2ClockSelection; /*!< Specifies DFSDM2 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Kernel_Clock_Source */ - - uint32_t Dfsdm2AudioClockSelection;/*!< Specifies DFSDM2 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Audio_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t SaiAClockSelection; /*!< Specifies SAI1_A Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockA_Clock_Source */ - - uint32_t SaiBClockSelection; /*!< Specifies SAI1_B Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockB_Clock_Source */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t PLLI2SSelection; /*!< Specifies PLL I2S Clock Source Selection. - This parameter can be a value of @ref RCCEx_PLL_I2S_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS and SDIO clocks. - This parameter is only available in STM32F469xx/STM32F479xx devices. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ -#endif /* STM32F469xx || STM32F479xx */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ - - uint32_t PLLSAIR; /*!< specifies the division factor for LTDC clock - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLSAI is selected as Clock Source LTDC */ - -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t PLLSAIDivR; /*!< Specifies the PLLSAI division factor for LTDC clock. - This parameter must be one value of @ref RCCEx_PLLSAI_DIVR */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Prescalers Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ -#endif /* STM32F469xx || STM32F479xx */ -}RCC_PeriphCLKInitTypeDef; - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ -#if defined(STM32F411xE) - uint32_t PLLI2SM; /*!< PLLM: Division factor for PLLI2S VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 62 */ -#endif /* STM32F411xE */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - Except for STM32F411xE devices where the Min_Data = 192. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Constants RCCEx Exported Constants - * @{ - */ - -/** @defgroup RCCEx_Periph_Clock_Selection RCC Periph Clock Selection - * @{ - */ -/* Peripheral Clock source for STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_TIM 0x00000004U -#define RCC_PERIPHCLK_RTC 0x00000008U -#define RCC_PERIPHCLK_FMPI2C1 0x00000010U -#define RCC_PERIPHCLK_CLK48 0x00000020U -#define RCC_PERIPHCLK_SDIO 0x00000040U -#define RCC_PERIPHCLK_PLLI2S 0x00000080U -#define RCC_PERIPHCLK_DFSDM1 0x00000100U -#define RCC_PERIPHCLK_DFSDM1_AUDIO 0x00000200U -#endif /* STM32F412Zx || STM32F412Vx) || STM32F412Rx || STM32F412Cx */ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_DFSDM2 0x00000400U -#define RCC_PERIPHCLK_DFSDM2_AUDIO 0x00000800U -#define RCC_PERIPHCLK_LPTIM1 0x00001000U -#define RCC_PERIPHCLK_SAIA 0x00002000U -#define RCC_PERIPHCLK_SAIB 0x00004000U -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F410xx ----------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_TIM 0x00000002U -#define RCC_PERIPHCLK_RTC 0x00000004U -#define RCC_PERIPHCLK_FMPI2C1 0x00000008U -#define RCC_PERIPHCLK_LPTIM1 0x00000010U -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_SAI1 0x00000004U -#define RCC_PERIPHCLK_SAI2 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_CEC 0x00000040U -#define RCC_PERIPHCLK_FMPI2C1 0x00000080U -#define RCC_PERIPHCLK_CLK48 0x00000100U -#define RCC_PERIPHCLK_SDIO 0x00000200U -#define RCC_PERIPHCLK_SPDIFRX 0x00000400U -#define RCC_PERIPHCLK_PLLI2S 0x00000800U -#endif /* STM32F446xx */ -/*-----------------------------------------------------------------------------*/ - -/*----------- Peripheral Clock source for STM32F469xx/STM32F479xx -------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#define RCC_PERIPHCLK_CLK48 0x00000080U -#define RCC_PERIPHCLK_SDIO 0x00000100U -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F42xxx/STM32F43xxx ---------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F40xxx/STM32F41xxx ---------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_RTC 0x00000002U -#define RCC_PERIPHCLK_PLLI2S 0x00000004U -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_TIM 0x00000008U -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || \ - defined(STM32F479xx) -/** @defgroup RCCEx_I2S_Clock_Source I2S Clock Source - * @{ - */ -#define RCC_I2SCLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SCLKSOURCE_EXT 0x00000001U -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -/** @defgroup RCCEx_PLLSAI_DIVR RCC PLLSAI DIVR - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIDIVR_2 0x00000000U -#define RCC_PLLSAIDIVR_4 0x00010000U -#define RCC_PLLSAIDIVR_8 0x00020000U -#define RCC_PLLSAIDIVR_16 0x00030000U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLI2SP_Clock_Divider RCC PLLI2SP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define RCC_PLLI2SP_DIV2 0x00000002U -#define RCC_PLLI2SP_DIV4 0x00000004U -#define RCC_PLLI2SP_DIV6 0x00000006U -#define RCC_PLLI2SP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLSAIP_Clock_Divider RCC PLLSAIP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIP_DIV2 0x00000002U -#define RCC_PLLSAIP_DIV4 0x00000004U -#define RCC_PLLSAIP_DIV6 0x00000006U -#define RCC_PLLSAIP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_SAI_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIACLKSOURCE_PLLI2S 0x00100000U -#define RCC_SAIACLKSOURCE_EXT 0x00200000U -/** - * @} - */ - -/** @defgroup RCCEx_SAI_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIBCLKSOURCE_PLLI2S 0x00400000U -#define RCC_SAIBCLKSOURCE_EXT 0x00800000U -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_DSI_Clock_Source RCC DSI Clock Source - * @{ - */ -#define RCC_DSICLKSOURCE_DSIPHY 0x00000000U -#define RCC_DSICLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_DSISEL) -/** - * @} - */ -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @defgroup RCCEx_SAI1_Clock_Source RCC SAI1 Clock Source - * @{ - */ -#define RCC_SAI1CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI1CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI1SRC_0) -#define RCC_SAI1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1SRC_1) -#define RCC_SAI1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_SAI2_Clock_Source RCC SAI2 Clock Source - * @{ - */ -#define RCC_SAI2CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI2CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI2SRC_0) -#define RCC_SAI2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI2SRC_1) -#define RCC_SAI2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CEC_Clock_Source RCC CEC Clock Source - * @{ - */ -#define RCC_CECCLKSOURCE_HSI 0x00000000U -#define RCC_CECCLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_CECSEL) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SPDIFRX_Clock_Source RCC SPDIFRX Clock Source - * @{ - */ -#define RCC_SPDIFRXCLKSOURCE_PLLR 0x00000000U -#define RCC_SPDIFRXCLKSOURCE_PLLI2SP ((uint32_t)RCC_DCKCFGR2_SPDIFRXSEL) -/** - * @} - */ - -#endif /* STM32F446xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_SAI1_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIACLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0) -#define RCC_SAIACLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1ASRC_1) -#define RCC_SAIACLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0 | RCC_DCKCFGR_SAI1ASRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_SAI1_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0) -#define RCC_SAIBCLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1BSRC_1) -#define RCC_SAIBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0 | RCC_DCKCFGR_SAI1BSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ - - -/** @defgroup RCCEx_DFSDM2_Audio_Clock_Source RCC DFSDM2 Audio Clock Source - * @{ - */ -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM2ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM2_Kernel_Clock_Source RCC DFSDM2 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM2CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM2CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_PLL_I2S_Clock_Source PLL I2S Clock Source - * @{ - */ -#define RCC_PLLI2SCLKSOURCE_PLLSRC 0x00000000U -#define RCC_PLLI2SCLKSOURCE_EXT ((uint32_t)RCC_PLLI2SCFGR_PLLI2SSRC) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Audio_Clock_Source RCC DFSDM1 Audio Clock Source - * @{ - */ -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Kernel_Clock_Source RCC DFSDM1 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM1CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLI2SQ ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) - -/** @defgroup RCCEx_I2S_APB_Clock_Source RCC I2S APB Clock Source - * @{ - */ -#define RCC_I2SAPBCLKSOURCE_PLLR 0x00000000U -#define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) -#define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_TIM_PRescaler_Selection RCC TIM PRescaler Selection - * @{ - */ -#define RCC_TIMPRES_DESACTIVATED ((uint8_t)0x00) -#define RCC_TIMPRES_ACTIVATED ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/** @defgroup RCCEx_LSE_Dual_Mode_Selection RCC LSE Dual Mode Selection - * @{ - */ -#define RCC_LSE_LOWPOWER_MODE ((uint8_t)0x00) -#define RCC_LSE_HIGHDRIVE_MODE ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_PLLI2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_I2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Macros RCCEx Exported Macros - * @{ - */ -/*------------------- STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOJ_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOK_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2D_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_GPIOJ_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOJEN)) -#define __HAL_RCC_GPIOK_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOKEN)) -#define __HAL_RCC_DMA2D_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2DEN)) -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) - -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) != RESET) -#define __HAL_RCC_GPIOK_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) != RESET) -#define __HAL_RCC_DMA2D_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) != RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) == RESET) -#define __HAL_RCC_GPIOK_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) == RESET) -#define __HAL_RCC_DMA2D_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) == RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ - #define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) - -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_SPI6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI6EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_LTDC_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_LTDCEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_DSI_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DSIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_SPI6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))!= RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))== RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_SPI6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) != RESET) -#define __HAL_RCC_LTDC_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) == RESET) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) != RESET) -#define __HAL_RCC_DSI_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_LTDCRST)) -#define __HAL_RCC_LTDC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_LTDCRST)) -#endif /* STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DSIRST)) -#define __HAL_RCC_DSI_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DSIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM3LPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_LTDCLPEN)) - -#define __HAL_RCC_LTDC_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_LTDCLPEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DSILPEN)) -#define __HAL_RCC_DSI_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DSILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------- STM32F40xxx/STM32F41xxx-----------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) - -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN))== RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) - -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) - /** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F415xx || STM32F417xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- STM32F401xE/STM32F401xC --------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -/** - * @} - */ -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -/** - * @} - */ -#endif /* STM32F401xC || STM32F401xE*/ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F410xx -------------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) != RESET) - -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB1) peripheral clock. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) - -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_RNGRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() -#define __HAL_RCC_AHB2_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) - -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) - -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -/** - * @} - */ - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F411xx -------------------------------*/ -#if defined(STM32F411xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEX_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -/** - * @} - */ -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F446xx -----------------------------*/ -#if defined(STM32F446xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN))!= RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPDIFRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CEC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_SPDIFRX_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPDIFRXEN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_CEC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CECEN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_CEC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_CEC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#define __HAL_RCC_SAI2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI2EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SAI2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#define __HAL_RCC_SAI2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI2RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI2RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI2LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI2LPEN)) -/** - * @} - */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx-------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_AES_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_AESEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) != RESET) -#define __HAL_RCC_AES_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) == RESET) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN3EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -#endif /* STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN))!= RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART9EN)) -#define __HAL_RCC_UART10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART10EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM1EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM2EN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) != RESET) -#define __HAL_RCC_UART10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) == RESET) -#define __HAL_RCC_UART10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F423xx) -#define __HAL_RCC_AES_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_AESRST)) -#define __HAL_RCC_AES_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_AESRST)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Cx) -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() - -#define __HAL_RCC_FSMC_FORCE_RESET() -#define __HAL_RCC_QSPI_FORCE_RESET() - -#define __HAL_RCC_FSMC_RELEASE_RESET() -#define __HAL_RCC_QSPI_RELEASE_RESET() -#endif /* STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_AESLPEN)) -#define __HAL_RCC_AES_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_AESLPEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------- PLL Configuration --------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz. - * - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - * @param __PLLR__ PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note This parameter is only available in STM32F446xx/STM32F469xx/STM32F479xx/ - STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__,__PLLR__) \ - (RCC->PLLCFGR = ((__RCC_PLLSource__) | (__PLLM__) | \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos) | \ - ((__PLLR__) << RCC_PLLCFGR_PLLR_Pos))) -#else -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432 - * Except for STM32F411xE devices where Min_Data = 192. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz, Except for STM32F411xE devices - * where frequency is between 192 and 432 MHz. - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__) \ - (RCC->PLLCFGR = (0x20000000U | (__RCC_PLLSource__) | (__PLLM__)| \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos))) - #endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------PLLI2S Configuration ---------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - -/** @brief Macros to enable or disable the PLLI2S. - * @note The PLLI2S is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLI2S_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = ENABLE) -#define __HAL_RCC_PLLI2S_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = DISABLE) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx */ -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SP__ specifies division factor for SPDIFRX Clock. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLI2SP parameter is only available with STM32F446xx Devices - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SP__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((((__PLLI2SP__) >> 1U) -1U) << RCC_PLLI2SCFGR_PLLI2SP_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#else -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SN__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = (((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F411xE) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note The PLLI2SM parameter is only used with STM32F411xE/STM32F410xx Devices - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLLI2S jitter. - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 192 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 192 and Max_Data = 432 MHz. - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_I2SCLK_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F411xE */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro used by the SAI HAL driver to configure the PLLI2S clock multiplication and division factors. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API) - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * @param __PLLI2SQ__ specifies the division factor for SAI1 clock. - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note the PLLI2SQ parameter is only available with STM32F427xx/437xx/429xx/439xx/469xx/479xx - * Devices and can be configured using the __HAL_RCC_PLLI2S_PLLSAICLK_CONFIG() macro - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_SAICLK_CONFIG(__PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SN__) << 6U) |\ - ((__PLLI2SQ__) << 24U) |\ - ((__PLLI2SR__) << 28U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------ PLLSAI Configuration ------------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to Enable or Disable the PLLISAI. - * @note The PLLSAI is only available with STM32F429x/439x Devices. - * @note The PLLSAI is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLSAI_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = ENABLE) -#define __HAL_RCC_PLLSAI_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = DISABLE) - -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIM__ specifies the division factor for PLLSAI VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLSAIM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * @note The PLLSAIM parameter is only used with STM32F446xx Devices - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for OTG FS, SDIO and RNG clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLSAIP parameter is only available with STM32F446xx Devices - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIM__, __PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = ((__PLLSAIM__) | \ - ((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for SDIO and CLK48 clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) |\ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) |\ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) |\ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) | \ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- PLLSAI/PLLI2S Dividers Configuration -------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivR__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SR) / __PLLI2SDivR__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(__PLLI2SDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, (__PLLI2SDivR__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLL. - * @param __PLLDivR__ specifies the PLL division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLR) / __PLLDivR__ - */ -#define __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(__PLLDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, ((__PLLDivR__)-1U)<<8U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivQ__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SQ) / __PLLI2SDivQ__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(__PLLI2SDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, (__PLLI2SDivQ__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLLSAI. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivQ__ specifies the PLLSAI division factor for SAI1 clock . - * This parameter must be a number between Min_Data = 1 and Max_Data = 32. - * SAI1 clock frequency = f(PLLSAIQ) / __PLLSAIDivQ__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(__PLLSAIDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, ((__PLLSAIDivQ__)-1U)<<8U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the LTDC clock Divider coming from PLLSAI. - * - * @note The LTDC peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivR__ specifies the PLLSAI division factor for LTDC clock . - * This parameter must be a number between Min_Data = 2 and Max_Data = 16. - * LTDC clock frequency = f(PLLSAIR) / __PLLSAIDivR__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(__PLLSAIDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, (__PLLSAIDivR__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- Peripheral Clock selection -----------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/** @brief Macro to configure the I2S clock source (I2SCLK). - * @note This function must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg RCC_I2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_CFGR_I2SSRC_BB = (__SOURCE__)) - - -/** @brief Macro to get the I2S clock source (I2SCLK). - * @retval The clock source can be one of the following values: - * @arg @ref RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg @ref RCC_I2SCLKSOURCE_EXT External clock mapped on the I2S_CKIN pin - * used as I2S clock source - */ -#define __HAL_RCC_GET_I2S_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_I2SSRC))) -#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block A clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to configure SAI1BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block B clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @brief Macro to configure SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI1 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_SAI1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_GET_SAI1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC)) - -/** @brief Macro to configure SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI2 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_SAI2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_GET_SAI2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC)) - -/** @brief Macro to configure I2S APB1 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the CEC clock. - * @param __SOURCE__ specifies the CEC clock source. - * This parameter can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_CEC_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CEC clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI488: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_GET_CEC_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -/** @brief Macro to configure the SPDIFRX clock. - * @param __SOURCE__ specifies the SPDIFRX clock source. - * This parameter can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_SPDIFRX_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SPDIFRX clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_GET_SPDIFRX_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL)) - -/** @brief Macro to configure the DSI clock. - * @param __SOURCE__ specifies the DSI clock source. - * This parameter can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_DSI_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the DSI clock. - * @retval The clock source can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_GET_DSI_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL)) - -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM1 clock. - * @param __DFSDM1_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM1_CONFIG(__DFSDM1_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM1_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM1 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM1_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM1 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM1AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM1AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL)) - -#if defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM2 clock. - * @param __DFSDM2_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM2_CONFIG(__DFSDM2_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM2_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM2 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM2_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM2 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM2AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM2 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM2AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL)) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockA clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKA_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC)) - -/** @brief Macro to configure SAI1 BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockB clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKB_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F413xx || STM32F423xx */ - -/** @brief Macro to configure I2S APB1 clock source selection. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @param __SOURCE__ specifies the I2S APB2 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the PLL I2S clock source (PLLI2SCLK). - * @note This macro must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLI2SCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - * @arg RCC_PLLI2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_PLL_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_PLLI2SCFGR_PLLI2SSRC_BB = (__SOURCE__)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macro to configure I2S clock source selection. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC, (__SOURCE__))) - -/** @brief Macro to Get I2S clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_GET_I2S_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the Timers clocks prescalers - * @note This feature is only available with STM32F429x/439x Devices. - * @param __PRESC__ specifies the Timers clocks prescalers selection - * This parameter can be one of the following values: - * @arg RCC_TIMPRES_DESACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1 or 2, - * else it is equal to [(HPRE * PPREx) / 2] if PPREx is corresponding to - * division by 4 or more. - * @arg RCC_TIMPRES_ACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1, 2 or 4, - * else it is equal to [(HPRE * PPREx) / 4] if PPREx is corresponding - * to division by 8 or more. - */ -#define __HAL_RCC_TIMCLKPRESCALER(__PRESC__) (*(__IO uint32_t *) RCC_DCKCFGR_TIMPRE_BB = (__PRESC__)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx) || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE ||\ - STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx ||\ - STM32F423xx */ - -/*----------------------------------------------------------------------------*/ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Enable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_ENABLE_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Disable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_DISABLE_IT() (RCC->CIR &= ~(RCC_CIR_PLLSAIRDYIE)) - -/** @brief Clear the PLLSAI RDY interrupt pending bits. - */ -#define __HAL_RCC_PLLSAI_CLEAR_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYF)) - -/** @brief Check the PLLSAI RDY interrupt has occurred or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_IT() ((RCC->CIR & (RCC_CIR_PLLSAIRDYIE)) == (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Check PLLSAI RDY flag is set or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_FLAG() ((RCC->CR & (RCC_CR_PLLSAIRDY)) == (RCC_CR_PLLSAIRDY)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macros to enable or disable the RCC MCO1 feature. - */ -#define __HAL_RCC_MCO1_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = ENABLE) -#define __HAL_RCC_MCO1_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = DISABLE) - -/** @brief Macros to enable or disable the RCC MCO2 feature. - */ -#define __HAL_RCC_MCO2_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = ENABLE) -#define __HAL_RCC_MCO2_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = DISABLE) - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RCCEx_Exported_Functions - * @{ - */ - -/** @addtogroup RCCEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); - -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -void HAL_RCCEx_SelectLSEMode(uint8_t Mode); -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#if defined(RCC_PLLI2S_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void); -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void); -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Constants RCCEx Private Constants - * @{ - */ - -/** @defgroup RCCEx_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -/* --- CR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of PLLSAION bit */ -#define RCC_PLLSAION_BIT_NUMBER 0x1CU -#define RCC_CR_PLLSAION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLSAION_BIT_NUMBER * 4U)) - -#define PLLSAI_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of PLLI2SON bit */ -#define RCC_PLLI2SON_BIT_NUMBER 0x1AU -#define RCC_CR_PLLI2SON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLI2SON_BIT_NUMBER * 4U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- DCKCFGR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of TIMPRE bit */ -#define RCC_DCKCFGR_OFFSET (RCC_OFFSET + 0x8CU) -#define RCC_TIMPRE_BIT_NUMBER 0x18U -#define RCC_DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (RCC_DCKCFGR_OFFSET * 32U) + (RCC_TIMPRE_BIT_NUMBER * 4U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F410xx || STM32F401xC ||\ - STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- CFGR Register ---*/ -#define RCC_CFGR_OFFSET (RCC_OFFSET + 0x08U) -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of I2SSRC bit */ -#define RCC_I2SSRC_BIT_NUMBER 0x17U -#define RCC_CFGR_I2SSRC_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_I2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/* --- PLLI2SCFGR Register ---*/ -#define RCC_PLLI2SCFGR_OFFSET (RCC_OFFSET + 0x84U) -/* Alias word address of PLLI2SSRC bit */ -#define RCC_PLLI2SSRC_BIT_NUMBER 0x16U -#define RCC_PLLI2SCFGR_PLLI2SSRC_BB (PERIPH_BB_BASE + (RCC_PLLI2SCFGR_OFFSET * 32U) + (RCC_PLLI2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/* Alias word address of MCO1EN bit */ -#define RCC_MCO1EN_BIT_NUMBER 0x8U -#define RCC_CFGR_MCO1EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO1EN_BIT_NUMBER * 4U)) - -/* Alias word address of MCO2EN bit */ -#define RCC_MCO2EN_BIT_NUMBER 0x9U -#define RCC_CFGR_MCO2EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO2EN_BIT_NUMBER * 4U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#define PLL_TIMEOUT_VALUE 2U /* 2 ms */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Macros RCCEx Private Macros - * @{ - */ -/** @defgroup RCCEx_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_PLLN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) -#define IS_RCC_PLLI2SN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000007FU)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000007U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000000FU)) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000001FU)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000FFFU)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000001FFU)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000003FFU)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00007FFFU)) -#endif /* STM32F413xx || STM32F423xx */ - -#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#define IS_RCC_PLLSAIQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAI_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLSAI_DIVR_VALUE(VALUE) (((VALUE) == RCC_PLLSAIDIVR_2) ||\ - ((VALUE) == RCC_PLLSAIDIVR_4) ||\ - ((VALUE) == RCC_PLLSAIDIVR_8) ||\ - ((VALUE) == RCC_PLLSAIDIVR_16)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SM_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 63U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_I2SAPBCLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == RCC_PLLI2SP_DIV2) ||\ - ((VALUE) == RCC_PLLI2SP_DIV4) ||\ - ((VALUE) == RCC_PLLI2SP_DIV6) ||\ - ((VALUE) == RCC_PLLI2SP_DIV8)) - -#define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_SAI1CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI1CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_EXT)) - -#define IS_RCC_SAI2CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI2CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLSRC)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CECCLKSOURCE(SOURCE) (((SOURCE) == RCC_CECCLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_CECCLKSOURCE_LSE)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_SPDIFRXCLKSOURCE(SOURCE) (((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DSIBYTELANECLKSOURCE(SOURCE) (((SOURCE) == RCC_DSICLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_DSICLKSOURCE_DSIPHY)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_PLLI2SCLKSOURCE_PLLSRC) || \ - ((__SOURCE__) == RCC_PLLI2SCLKSOURCE_EXT)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLI2SQ)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM1CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S2)) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_DFSDM2CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM2CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM2AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S2)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_SAIACLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIACLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLSRC)) - -#define IS_RCC_SAIBCLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIBCLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLSRC)) - -#define IS_RCC_PLL_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#endif /* STM32F413xx || STM32F423xx */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_PLLI2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_I2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_EX_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc_ex.h + * @author MCD Application Team + * @brief Header file of RCC HAL Extension module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_RCC_EX_H +#define __STM32F4xx_HAL_RCC_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup RCCEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup RCCEx_Exported_Types RCCEx Exported Types + * @{ + */ + +/** + * @brief RCC PLL configuration structure definition + */ +typedef struct +{ + uint32_t PLLState; /*!< The new state of the PLL. + This parameter can be a value of @ref RCC_PLL_Config */ + + uint32_t PLLSource; /*!< RCC_PLLSource: PLL entry clock source. + This parameter must be a value of @ref RCC_PLL_Clock_Source */ + + uint32_t PLLM; /*!< PLLM: Division factor for PLL VCO input clock. + This parameter must be a number between Min_Data = 0 and Max_Data = 63 */ + + uint32_t PLLN; /*!< PLLN: Multiplication factor for PLL VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432 + except for STM32F411xE devices where the Min_Data = 192 */ + + uint32_t PLLP; /*!< PLLP: Division factor for main system clock (SYSCLK). + This parameter must be a value of @ref RCC_PLLP_Clock_Divider */ + + uint32_t PLLQ; /*!< PLLQ: Division factor for OTG FS, SDIO and RNG clocks. + This parameter must be a number between Min_Data = 2 and Max_Data = 15 */ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) + uint32_t PLLR; /*!< PLLR: PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. + This parameter is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx + and STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. + This parameter must be a number between Min_Data = 2 and Max_Data = 7 */ +#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +}RCC_PLLInitTypeDef; + +#if defined(STM32F446xx) +/** + * @brief PLLI2S Clock structure definition + */ +typedef struct +{ + uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ + + uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ + + uint32_t PLLI2SP; /*!< Specifies division factor for SPDIFRX Clock. + This parameter must be a value of @ref RCCEx_PLLI2SP_Clock_Divider */ + + uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 15. + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ + + uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 7. + This parameter will be used only when PLLI2S is selected as Clock Source I2S */ +}RCC_PLLI2SInitTypeDef; + +/** + * @brief PLLSAI Clock structure definition + */ +typedef struct +{ + uint32_t PLLSAIM; /*!< Specifies division factor for PLL VCO input clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ + + uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ + + uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS, SDIO and RNG clocks. + This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ + + uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 15. + This parameter will be used only when PLLSAI is selected as Clock Source SAI */ +}RCC_PLLSAIInitTypeDef; + +/** + * @brief RCC extended clocks structure definition + */ +typedef struct +{ + uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. + This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ + + RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ + + uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ + + uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLLSAI is selected as Clock Source SAI */ + + uint32_t Sai1ClockSelection; /*!< Specifies SAI1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_SAI1_Clock_Source */ + + uint32_t Sai2ClockSelection; /*!< Specifies SAI2 Clock Source Selection. + This parameter can be a value of @ref RCCEx_SAI2_Clock_Source */ + + uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ + + uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. + This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ + + uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. + This parameter can be a value of @ref RCC_RTC_Clock_Source */ + + uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. + This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ + + uint32_t CecClockSelection; /*!< Specifies CEC Clock Source Selection. + This parameter can be a value of @ref RCCEx_CEC_Clock_Source */ + + uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ + + uint32_t SpdifClockSelection; /*!< Specifies SPDIFRX Clock Source Selection. + This parameter can be a value of @ref RCCEx_SPDIFRX_Clock_Source */ + + uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. + This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ + + uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. + This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ +}RCC_PeriphCLKInitTypeDef; +#endif /* STM32F446xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** + * @brief RCC extended clocks structure definition + */ +typedef struct +{ + uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. + This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ + + uint32_t I2SClockSelection; /*!< Specifies RTC Clock Source Selection. + This parameter can be a value of @ref RCCEx_I2S_APB_Clock_Source */ + + uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. + This parameter can be a value of @ref RCC_RTC_Clock_Source */ + + uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ + + uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ + + uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. + This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ +}RCC_PeriphCLKInitTypeDef; +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief PLLI2S Clock structure definition + */ +typedef struct +{ + uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ + + uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ + + uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 15. + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ + + uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 7. + This parameter will be used only when PLLI2S is selected as Clock Source I2S */ +}RCC_PLLI2SInitTypeDef; + +/** + * @brief RCC extended clocks structure definition + */ +typedef struct +{ + uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. + This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ + + RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source I2S */ + +#if defined(STM32F413xx) || defined(STM32F423xx) + uint32_t PLLDivR; /*!< Specifies the PLL division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLL is selected as Clock Source SAI */ + + uint32_t PLLI2SDivR; /*!< Specifies the PLLI2S division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ +#endif /* STM32F413xx || STM32F423xx */ + + uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ + + uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. + This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ + + uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. + This parameter can be a value of @ref RCC_RTC_Clock_Source */ + + uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. + This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ + + uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ + + uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. + This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ + + uint32_t Dfsdm1ClockSelection; /*!< Specifies DFSDM1 Clock Selection. + This parameter can be a value of @ref RCCEx_DFSDM1_Kernel_Clock_Source */ + + uint32_t Dfsdm1AudioClockSelection;/*!< Specifies DFSDM1 Audio Clock Selection. + This parameter can be a value of @ref RCCEx_DFSDM1_Audio_Clock_Source */ + +#if defined(STM32F413xx) || defined(STM32F423xx) + uint32_t Dfsdm2ClockSelection; /*!< Specifies DFSDM2 Clock Selection. + This parameter can be a value of @ref RCCEx_DFSDM2_Kernel_Clock_Source */ + + uint32_t Dfsdm2AudioClockSelection;/*!< Specifies DFSDM2 Audio Clock Selection. + This parameter can be a value of @ref RCCEx_DFSDM2_Audio_Clock_Source */ + + uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. + This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ + + uint32_t SaiAClockSelection; /*!< Specifies SAI1_A Clock Prescalers Selection + This parameter can be a value of @ref RCCEx_SAI1_BlockA_Clock_Source */ + + uint32_t SaiBClockSelection; /*!< Specifies SAI1_B Clock Prescalers Selection + This parameter can be a value of @ref RCCEx_SAI1_BlockB_Clock_Source */ +#endif /* STM32F413xx || STM32F423xx */ + + uint32_t PLLI2SSelection; /*!< Specifies PLL I2S Clock Source Selection. + This parameter can be a value of @ref RCCEx_PLL_I2S_Clock_Source */ + + uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. + This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ +}RCC_PeriphCLKInitTypeDef; +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/** + * @brief PLLI2S Clock structure definition + */ +typedef struct +{ + uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 7. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI1 clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 15. + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ +}RCC_PLLI2SInitTypeDef; + +/** + * @brief PLLSAI Clock structure definition + */ +typedef struct +{ + uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432. + This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ +#if defined(STM32F469xx) || defined(STM32F479xx) + uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS and SDIO clocks. + This parameter is only available in STM32F469xx/STM32F479xx devices. + This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ +#endif /* STM32F469xx || STM32F479xx */ + + uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI1 clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 15. + This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ + + uint32_t PLLSAIR; /*!< specifies the division factor for LTDC clock + This parameter must be a number between Min_Data = 2 and Max_Data = 7. + This parameter will be used only when PLLSAI is selected as Clock Source LTDC */ + +}RCC_PLLSAIInitTypeDef; + +/** + * @brief RCC extended clocks structure definition + */ +typedef struct +{ + uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. + This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ + + RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ + + uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLLI2S is selected as Clock Source SAI */ + + uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. + This parameter must be a number between Min_Data = 1 and Max_Data = 32 + This parameter will be used only when PLLSAI is selected as Clock Source SAI */ + + uint32_t PLLSAIDivR; /*!< Specifies the PLLSAI division factor for LTDC clock. + This parameter must be one value of @ref RCCEx_PLLSAI_DIVR */ + + uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. + This parameter can be a value of @ref RCC_RTC_Clock_Source */ + + uint8_t TIMPresSelection; /*!< Specifies TIM Clock Prescalers Selection. + This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ +#if defined(STM32F469xx) || defined(STM32F479xx) + uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. + This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ + + uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. + This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ +#endif /* STM32F469xx || STM32F479xx */ +}RCC_PeriphCLKInitTypeDef; + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +/** + * @brief PLLI2S Clock structure definition + */ +typedef struct +{ +#if defined(STM32F411xE) + uint32_t PLLI2SM; /*!< PLLM: Division factor for PLLI2S VCO input clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 62 */ +#endif /* STM32F411xE */ + + uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. + This parameter must be a number between Min_Data = 50 and Max_Data = 432 + Except for STM32F411xE devices where the Min_Data = 192. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. + This parameter must be a number between Min_Data = 2 and Max_Data = 7. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + +}RCC_PLLI2SInitTypeDef; + +/** + * @brief RCC extended clocks structure definition + */ +typedef struct +{ + uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. + This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ + + RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. + This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ + + uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. + This parameter can be a value of @ref RCC_RTC_Clock_Source */ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) + uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. + This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ +}RCC_PeriphCLKInitTypeDef; +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup RCCEx_Exported_Constants RCCEx Exported Constants + * @{ + */ + +/** @defgroup RCCEx_Periph_Clock_Selection RCC Periph Clock Selection + * @{ + */ +/* Peripheral Clock source for STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +#define RCC_PERIPHCLK_I2S_APB1 0x00000001U +#define RCC_PERIPHCLK_I2S_APB2 0x00000002U +#define RCC_PERIPHCLK_TIM 0x00000004U +#define RCC_PERIPHCLK_RTC 0x00000008U +#define RCC_PERIPHCLK_FMPI2C1 0x00000010U +#define RCC_PERIPHCLK_CLK48 0x00000020U +#define RCC_PERIPHCLK_SDIO 0x00000040U +#define RCC_PERIPHCLK_PLLI2S 0x00000080U +#define RCC_PERIPHCLK_DFSDM1 0x00000100U +#define RCC_PERIPHCLK_DFSDM1_AUDIO 0x00000200U +#endif /* STM32F412Zx || STM32F412Vx) || STM32F412Rx || STM32F412Cx */ +#if defined(STM32F413xx) || defined(STM32F423xx) +#define RCC_PERIPHCLK_DFSDM2 0x00000400U +#define RCC_PERIPHCLK_DFSDM2_AUDIO 0x00000800U +#define RCC_PERIPHCLK_LPTIM1 0x00001000U +#define RCC_PERIPHCLK_SAIA 0x00002000U +#define RCC_PERIPHCLK_SAIB 0x00004000U +#endif /* STM32F413xx || STM32F423xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------- Peripheral Clock source for STM32F410xx ----------------*/ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define RCC_PERIPHCLK_I2S 0x00000001U +#define RCC_PERIPHCLK_TIM 0x00000002U +#define RCC_PERIPHCLK_RTC 0x00000004U +#define RCC_PERIPHCLK_FMPI2C1 0x00000008U +#define RCC_PERIPHCLK_LPTIM1 0x00000010U +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ +/*----------------------------------------------------------------------------*/ + +/*------------------- Peripheral Clock source for STM32F446xx ----------------*/ +#if defined(STM32F446xx) +#define RCC_PERIPHCLK_I2S_APB1 0x00000001U +#define RCC_PERIPHCLK_I2S_APB2 0x00000002U +#define RCC_PERIPHCLK_SAI1 0x00000004U +#define RCC_PERIPHCLK_SAI2 0x00000008U +#define RCC_PERIPHCLK_TIM 0x00000010U +#define RCC_PERIPHCLK_RTC 0x00000020U +#define RCC_PERIPHCLK_CEC 0x00000040U +#define RCC_PERIPHCLK_FMPI2C1 0x00000080U +#define RCC_PERIPHCLK_CLK48 0x00000100U +#define RCC_PERIPHCLK_SDIO 0x00000200U +#define RCC_PERIPHCLK_SPDIFRX 0x00000400U +#define RCC_PERIPHCLK_PLLI2S 0x00000800U +#endif /* STM32F446xx */ +/*-----------------------------------------------------------------------------*/ + +/*----------- Peripheral Clock source for STM32F469xx/STM32F479xx -------------*/ +#if defined(STM32F469xx) || defined(STM32F479xx) +#define RCC_PERIPHCLK_I2S 0x00000001U +#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U +#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U +#define RCC_PERIPHCLK_LTDC 0x00000008U +#define RCC_PERIPHCLK_TIM 0x00000010U +#define RCC_PERIPHCLK_RTC 0x00000020U +#define RCC_PERIPHCLK_PLLI2S 0x00000040U +#define RCC_PERIPHCLK_CLK48 0x00000080U +#define RCC_PERIPHCLK_SDIO 0x00000100U +#endif /* STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*-------- Peripheral Clock source for STM32F42xxx/STM32F43xxx ---------------*/ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +#define RCC_PERIPHCLK_I2S 0x00000001U +#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U +#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U +#define RCC_PERIPHCLK_LTDC 0x00000008U +#define RCC_PERIPHCLK_TIM 0x00000010U +#define RCC_PERIPHCLK_RTC 0x00000020U +#define RCC_PERIPHCLK_PLLI2S 0x00000040U +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ +/*----------------------------------------------------------------------------*/ + +/*-------- Peripheral Clock source for STM32F40xxx/STM32F41xxx ---------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +#define RCC_PERIPHCLK_I2S 0x00000001U +#define RCC_PERIPHCLK_RTC 0x00000002U +#define RCC_PERIPHCLK_PLLI2S 0x00000004U +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +#define RCC_PERIPHCLK_TIM 0x00000008U +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ +/*----------------------------------------------------------------------------*/ +/** + * @} + */ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || \ + defined(STM32F479xx) +/** @defgroup RCCEx_I2S_Clock_Source I2S Clock Source + * @{ + */ +#define RCC_I2SCLKSOURCE_PLLI2S 0x00000000U +#define RCC_I2SCLKSOURCE_EXT 0x00000001U +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ + +/** @defgroup RCCEx_PLLSAI_DIVR RCC PLLSAI DIVR + * @{ + */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +#define RCC_PLLSAIDIVR_2 0x00000000U +#define RCC_PLLSAIDIVR_4 0x00010000U +#define RCC_PLLSAIDIVR_8 0x00020000U +#define RCC_PLLSAIDIVR_16 0x00030000U +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_PLLI2SP_Clock_Divider RCC PLLI2SP Clock Divider + * @{ + */ +#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) +#define RCC_PLLI2SP_DIV2 0x00000002U +#define RCC_PLLI2SP_DIV4 0x00000004U +#define RCC_PLLI2SP_DIV6 0x00000006U +#define RCC_PLLI2SP_DIV8 0x00000008U +#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +/** + * @} + */ + +/** @defgroup RCCEx_PLLSAIP_Clock_Divider RCC PLLSAIP Clock Divider + * @{ + */ +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define RCC_PLLSAIP_DIV2 0x00000002U +#define RCC_PLLSAIP_DIV4 0x00000004U +#define RCC_PLLSAIP_DIV6 0x00000006U +#define RCC_PLLSAIP_DIV8 0x00000008U +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @defgroup RCCEx_SAI_BlockA_Clock_Source RCC SAI BlockA Clock Source + * @{ + */ +#define RCC_SAIACLKSOURCE_PLLSAI 0x00000000U +#define RCC_SAIACLKSOURCE_PLLI2S 0x00100000U +#define RCC_SAIACLKSOURCE_EXT 0x00200000U +/** + * @} + */ + +/** @defgroup RCCEx_SAI_BlockB_Clock_Source RCC SAI BlockB Clock Source + * @{ + */ +#define RCC_SAIBCLKSOURCE_PLLSAI 0x00000000U +#define RCC_SAIBCLKSOURCE_PLLI2S 0x00400000U +#define RCC_SAIBCLKSOURCE_EXT 0x00800000U +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source + * @{ + */ +#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U +#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR_CK48MSEL) +/** + * @} + */ + +/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source + * @{ + */ +#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U +#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_SDIOSEL) +/** + * @} + */ + +/** @defgroup RCCEx_DSI_Clock_Source RCC DSI Clock Source + * @{ + */ +#define RCC_DSICLKSOURCE_DSIPHY 0x00000000U +#define RCC_DSICLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_DSISEL) +/** + * @} + */ +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F446xx) +/** @defgroup RCCEx_SAI1_Clock_Source RCC SAI1 Clock Source + * @{ + */ +#define RCC_SAI1CLKSOURCE_PLLSAI 0x00000000U +#define RCC_SAI1CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI1SRC_0) +#define RCC_SAI1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1SRC_1) +#define RCC_SAI1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1SRC) +/** + * @} + */ + +/** @defgroup RCCEx_SAI2_Clock_Source RCC SAI2 Clock Source + * @{ + */ +#define RCC_SAI2CLKSOURCE_PLLSAI 0x00000000U +#define RCC_SAI2CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI2SRC_0) +#define RCC_SAI2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI2SRC_1) +#define RCC_SAI2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI2SRC) +/** + * @} + */ + +/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source + * @{ + */ +#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U +#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) +#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) +#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) +/** + * @} + */ + +/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source + * @{ + */ +#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U +#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) +#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) +#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) +/** + * @} + */ + +/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source + * @{ + */ +#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U +#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) +#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) +/** + * @} + */ + +/** @defgroup RCCEx_CEC_Clock_Source RCC CEC Clock Source + * @{ + */ +#define RCC_CECCLKSOURCE_HSI 0x00000000U +#define RCC_CECCLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_CECSEL) +/** + * @} + */ + +/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source + * @{ + */ +#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U +#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR2_CK48MSEL) +/** + * @} + */ + +/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source + * @{ + */ +#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U +#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) +/** + * @} + */ + +/** @defgroup RCCEx_SPDIFRX_Clock_Source RCC SPDIFRX Clock Source + * @{ + */ +#define RCC_SPDIFRXCLKSOURCE_PLLR 0x00000000U +#define RCC_SPDIFRXCLKSOURCE_PLLI2SP ((uint32_t)RCC_DCKCFGR2_SPDIFRXSEL) +/** + * @} + */ + +#endif /* STM32F446xx */ + +#if defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup RCCEx_SAI1_BlockA_Clock_Source RCC SAI BlockA Clock Source + * @{ + */ +#define RCC_SAIACLKSOURCE_PLLI2SR 0x00000000U +#define RCC_SAIACLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0) +#define RCC_SAIACLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1ASRC_1) +#define RCC_SAIACLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0 | RCC_DCKCFGR_SAI1ASRC_1) +/** + * @} + */ + +/** @defgroup RCCEx_SAI1_BlockB_Clock_Source RCC SAI BlockB Clock Source + * @{ + */ +#define RCC_SAIBCLKSOURCE_PLLI2SR 0x00000000U +#define RCC_SAIBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0) +#define RCC_SAIBCLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1BSRC_1) +#define RCC_SAIBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0 | RCC_DCKCFGR_SAI1BSRC_1) +/** + * @} + */ + +/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source + * @{ + */ +#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U +#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) +#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) +#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) +/** + * @} + */ + + +/** @defgroup RCCEx_DFSDM2_Audio_Clock_Source RCC DFSDM2 Audio Clock Source + * @{ + */ +#define RCC_DFSDM2AUDIOCLKSOURCE_I2S1 0x00000000U +#define RCC_DFSDM2AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM2ASEL) +/** + * @} + */ + +/** @defgroup RCCEx_DFSDM2_Kernel_Clock_Source RCC DFSDM2 Kernel Clock Source + * @{ + */ +#define RCC_DFSDM2CLKSOURCE_PCLK2 0x00000000U +#define RCC_DFSDM2CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) +/** + * @} + */ + +#endif /* STM32F413xx || STM32F423xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup RCCEx_PLL_I2S_Clock_Source PLL I2S Clock Source + * @{ + */ +#define RCC_PLLI2SCLKSOURCE_PLLSRC 0x00000000U +#define RCC_PLLI2SCLKSOURCE_EXT ((uint32_t)RCC_PLLI2SCFGR_PLLI2SSRC) +/** + * @} + */ + +/** @defgroup RCCEx_DFSDM1_Audio_Clock_Source RCC DFSDM1 Audio Clock Source + * @{ + */ +#define RCC_DFSDM1AUDIOCLKSOURCE_I2S1 0x00000000U +#define RCC_DFSDM1AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) +/** + * @} + */ + +/** @defgroup RCCEx_DFSDM1_Kernel_Clock_Source RCC DFSDM1 Kernel Clock Source + * @{ + */ +#define RCC_DFSDM1CLKSOURCE_PCLK2 0x00000000U +#define RCC_DFSDM1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) +/** + * @} + */ + +/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source + * @{ + */ +#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U +#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) +#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) +#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) +/** + * @} + */ + +/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source + * @{ + */ +#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U +#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) +#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) +#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) +/** + * @} + */ + +/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source + * @{ + */ +#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U +#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) +#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) +/** + * @} + */ + +/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source + * @{ + */ +#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U +#define RCC_CLK48CLKSOURCE_PLLI2SQ ((uint32_t)RCC_DCKCFGR2_CK48MSEL) +/** + * @} + */ + +/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source + * @{ + */ +#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U +#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) +/** + * @} + */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) + +/** @defgroup RCCEx_I2S_APB_Clock_Source RCC I2S APB Clock Source + * @{ + */ +#define RCC_I2SAPBCLKSOURCE_PLLR 0x00000000U +#define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) +#define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) +/** + * @} + */ + +/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source + * @{ + */ +#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U +#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) +#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) +/** + * @} + */ + +/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source + * @{ + */ +#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U +#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) +#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) +#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) +/** + * @} + */ +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup RCCEx_TIM_PRescaler_Selection RCC TIM PRescaler Selection + * @{ + */ +#define RCC_TIMPRES_DESACTIVATED ((uint8_t)0x00) +#define RCC_TIMPRES_ACTIVATED ((uint8_t)0x01) +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ + STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +/** @defgroup RCCEx_LSE_Dual_Mode_Selection RCC LSE Dual Mode Selection + * @{ + */ +#define RCC_LSE_LOWPOWER_MODE ((uint8_t)0x00) +#define RCC_LSE_HIGHDRIVE_MODE ((uint8_t)0x01) +/** + * @} + */ +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx ||\ + STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source + * @{ + */ +#define RCC_MCO2SOURCE_SYSCLK 0x00000000U +#define RCC_MCO2SOURCE_PLLI2SCLK RCC_CFGR_MCO2_0 +#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 +#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || + STM32F412Rx || STM32F413xx | STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source + * @{ + */ +#define RCC_MCO2SOURCE_SYSCLK 0x00000000U +#define RCC_MCO2SOURCE_I2SCLK RCC_CFGR_MCO2_0 +#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 +#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 +/** + * @} + */ +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup RCCEx_Exported_Macros RCCEx Exported Macros + * @{ + */ +/*------------------- STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx --------*/ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOJ_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOK_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DMA2D_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) +#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) +#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) +#define __HAL_RCC_GPIOJ_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOJEN)) +#define __HAL_RCC_GPIOK_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOKEN)) +#define __HAL_RCC_DMA2D_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2DEN)) +#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) +#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) +#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) +#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) +#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) +#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) + +/** + * @brief Enable ETHERNET clock. + */ +#define __HAL_RCC_ETH_CLK_ENABLE() do { \ + __HAL_RCC_ETHMAC_CLK_ENABLE(); \ + __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ + __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ + } while(0U) +/** + * @brief Disable ETHERNET clock. + */ +#define __HAL_RCC_ETH_CLK_DISABLE() do { \ + __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ + __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ + __HAL_RCC_ETHMAC_CLK_DISABLE(); \ + } while(0U) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) +#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) +#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) +#define __HAL_RCC_GPIOJ_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) != RESET) +#define __HAL_RCC_GPIOK_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) != RESET) +#define __HAL_RCC_DMA2D_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) != RESET) +#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) +#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) +#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) +#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) +#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) +#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ + __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ + __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) + +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) +#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) +#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) +#define __HAL_RCC_GPIOJ_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) == RESET) +#define __HAL_RCC_GPIOK_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) == RESET) +#define __HAL_RCC_DMA2D_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) == RESET) +#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) +#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) +#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) +#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) +#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ + __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ + __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ + #define __HAL_RCC_DCMI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) + +#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) +#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_HASH_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) +#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) +#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ + +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) + +#define __HAL_RCC_RNG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) +#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) + +#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) +#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) +#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) + +#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) +#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) +#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ + +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) + +#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) +#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FMC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + + +/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) +#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) +#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) +#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) +#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) +#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) +#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) +#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) +#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) +#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) +#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) +#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) +#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) +#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) +#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) +#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) +#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) +#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) +#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) +#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) +#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) +#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) +#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) +#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) +#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) +#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) +#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) +#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) +#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) +#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) +#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) +#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) +#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) +#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) +#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) +#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) +#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) +#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) +#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) +#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) +#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) +#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) +#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) +#define __HAL_RCC_SPI6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI6EN)) +#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) + +#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_LTDC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_LTDC_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_LTDCEN)) +#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_DSI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_DSI_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DSIEN)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) +#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) +#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) +#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) +#define __HAL_RCC_SPI6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) != RESET) +#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))!= RESET) + +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))== RESET) +#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) +#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) +#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) +#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) +#define __HAL_RCC_SPI6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) == RESET) +#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) + +#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_LTDC_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) != RESET) +#define __HAL_RCC_LTDC_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) == RESET) +#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_DSI_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) != RESET) +#define __HAL_RCC_DSI_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) == RESET) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) +#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) +#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_GPIOJ_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOJRST)) +#define __HAL_RCC_GPIOK_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOKRST)) +#define __HAL_RCC_DMA2D_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2DRST)) +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) +#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) +#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_GPIOJ_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOJRST)) +#define __HAL_RCC_GPIOK_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOKRST)) +#define __HAL_RCC_DMA2D_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2DRST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) + +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) + +#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) +#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) +#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) + +#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) +#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) +#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) +#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) +#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) +#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) +#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) + +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) +#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) +#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) +#define __HAL_RCC_SPI6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI6RST)) +#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) + +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) +#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) +#define __HAL_RCC_SPI6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI6RST)) +#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) + +#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_LTDC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_LTDCRST)) +#define __HAL_RCC_LTDC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_LTDCRST)) +#endif /* STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_DSI_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DSIRST)) +#define __HAL_RCC_DSI_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DSIRST)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) +#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) +#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) +#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOJLPEN)) +#define __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOKLPEN)) +#define __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM3LPEN)) +#define __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2DLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) +#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) +#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) +#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOJLPEN)) +#define __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOKLPEN)) +#define __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2DLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) + +#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) +#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) + +#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) +#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) + +#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) +#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) +#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) + +#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) +#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) +#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) +#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) +#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) +#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) +#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) +#define __HAL_RCC_SPI6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI6LPEN)) +#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) + +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) +#define __HAL_RCC_SPI6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI6LPEN)) +#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) + +#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_LTDC_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_LTDCLPEN)) + +#define __HAL_RCC_LTDC_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_LTDCLPEN)) +#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define __HAL_RCC_DSI_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DSILPEN)) +#define __HAL_RCC_DSI_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DSILPEN)) +#endif /* STM32F469xx || STM32F479xx */ +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*----------------------------------- STM32F40xxx/STM32F41xxx-----------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) +#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) +#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) +#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) +#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +#if defined(STM32F407xx)|| defined(STM32F417xx) +/** + * @brief Enable ETHERNET clock. + */ +#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ETH_CLK_ENABLE() do { \ + __HAL_RCC_ETHMAC_CLK_ENABLE(); \ + __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ + __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ + } while(0U) + +/** + * @brief Disable ETHERNET clock. + */ +#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) +#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) +#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) +#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) +#define __HAL_RCC_ETH_CLK_DISABLE() do { \ + __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ + __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ + __HAL_RCC_ETHMAC_CLK_DISABLE(); \ + } while(0U) +#endif /* STM32F407xx || STM32F417xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) +#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) +#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) + +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) +#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) +#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN))== RESET) +#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +#if defined(STM32F407xx)|| defined(STM32F417xx) +/** + * @brief Enable ETHERNET clock. + */ +#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) +#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) +#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) +#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) +#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ + __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ + __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) +/** + * @brief Disable ETHERNET clock. + */ +#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) +#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) +#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) +#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) +#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ + __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ + __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) +#endif /* STM32F407xx || STM32F417xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) + +#define __HAL_RCC_RNG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) + +#if defined(STM32F407xx)|| defined(STM32F417xx) +#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) +#endif /* STM32F407xx || STM32F417xx */ + +#if defined(STM32F415xx) || defined(STM32F417xx) +#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_HASH_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) +#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) +#endif /* STM32F415xx || STM32F417xx */ +/** + * @} + */ + + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) + +#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) +#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) + +#if defined(STM32F407xx)|| defined(STM32F417xx) +#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) +#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) +#endif /* STM32F407xx || STM32F417xx */ + +#if defined(STM32F415xx) || defined(STM32F417xx) +#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) +#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) + +#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) +#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) +#endif /* STM32F415xx || STM32F417xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) +#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) +#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) +#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) +#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) +#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) +#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) +#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) +#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) +#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) +#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) +#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) +#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) +#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) +#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) +#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) +#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) +#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) +#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) +#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) +#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) +#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) +#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) +#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) +#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) +#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) +#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) +#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) +#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) +#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) +#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) +#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) +#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) + /** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) +#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) +#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) +#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) +#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) +#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) + +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) +#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) +#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) +#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) +#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) +#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) +#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) +#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) + +#if defined(STM32F407xx)|| defined(STM32F417xx) +#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) +#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) +#endif /* STM32F407xx || STM32F417xx */ + +#if defined(STM32F415xx) || defined(STM32F417xx) +#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) +#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) + +#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) +#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) +#endif /* STM32F415xx || STM32F417xx */ + +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) + +#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) + +#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) +#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) + +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) + +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) +#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) +#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) +#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) +#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) +#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) +#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) + +#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) +#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) + +#if defined(STM32F407xx)|| defined(STM32F417xx) +#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) +#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) +#endif /* STM32F407xx || STM32F417xx */ + +#if defined(STM32F415xx) || defined(STM32F417xx) +#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) +#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) + +#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) +#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) +#endif /* STM32F415xx || STM32F417xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) +#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) + +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------------- STM32F401xE/STM32F401xC --------------------------*/ +#if defined(STM32F401xC) || defined(STM32F401xE) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) + +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) + +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) +/** + * @} + */ +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) + +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) + +#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) + +#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) + +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) + +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +/** + * @} + */ +#endif /* STM32F401xC || STM32F401xE*/ +/*----------------------------------------------------------------------------*/ + +/*-------------------------------- STM32F410xx -------------------------------*/ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RNG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_RNGEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) +#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) != RESET) + +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB1) peripheral clock. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) +#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) +#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) +#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) +#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) +#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) +#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) +#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) + +#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) +#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) +#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) +#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @{ + */ +#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) +#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) +#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) + +#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) +#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) +#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_RNGRST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_RNGRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() +#define __HAL_RCC_AHB2_RELEASE_RESET() +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() +#define __HAL_RCC_AHB3_RELEASE_RESET() +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) +#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) + +#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) +#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) +#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_RNGLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) + +#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_RNGLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) +#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) + +#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) +#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @{ + */ +#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) +#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) +#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) +/** + * @} + */ + +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ +/*----------------------------------------------------------------------------*/ + +/*-------------------------------- STM32F411xx -------------------------------*/ +#if defined(STM32F411xE) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) + +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEX_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @{ + */ +#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) +#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) + +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) +#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) + +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) + +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) + +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @{ + */ +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @{ + */ +#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) + +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) +/** + * @} + */ +#endif /* STM32F411xE */ +/*----------------------------------------------------------------------------*/ + +/*---------------------------------- STM32F446xx -----------------------------*/ +#if defined(STM32F446xx) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) +#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) +#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) +#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) +#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) +#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN))!= RESET) +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) + +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) +#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) +#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) +#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) +#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) + +#define __HAL_RCC_RNG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) +#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) + +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) + +#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) +#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FMC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) +#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) +#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) + +#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) +#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPDIFRX_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CEC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_DAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) +#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) +#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) +#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) +#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) +#define __HAL_RCC_SPDIFRX_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPDIFRXEN)) +#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) +#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) +#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) +#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) +#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) +#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) +#define __HAL_RCC_CEC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CECEN)) +#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) +#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) +#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) +#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) +#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) +#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) +#define __HAL_RCC_SPDIFRX_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) != RESET) +#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) +#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) +#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) +#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) +#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) +#define __HAL_RCC_CEC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) != RESET) +#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) +#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) +#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) +#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) +#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) +#define __HAL_RCC_SPDIFRX_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) == RESET) +#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) +#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) +#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) +#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) +#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) +#define __HAL_RCC_CEC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) == RESET) +#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SAI2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) +#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) +#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) +#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) +#define __HAL_RCC_SAI2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI2EN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) +#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) +#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) +#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) +#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) +#define __HAL_RCC_SAI2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) != RESET) + +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) +#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) +#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) +#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) +#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) +#define __HAL_RCC_SAI2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) +#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) + +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) + +#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) +#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) + +#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) +#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_SPDIFRX_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPDIFRXRST)) +#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_CEC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CECRST)) +#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) + +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) +#define __HAL_RCC_SPDIFRX_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPDIFRXRST)) +#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) +#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) +#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) +#define __HAL_RCC_CEC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CECRST)) +#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) +#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) +#define __HAL_RCC_SAI2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI2RST)) +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) + +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) +#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) +#define __HAL_RCC_SAI2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI2RST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) +#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) +#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) + +#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) +#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) + +#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) +#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) +#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) + +#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) +#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_SPDIFRX_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPDIFRXLPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_CEC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CECLPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) +#define __HAL_RCC_SPDIFRX_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPDIFRXLPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) +#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) +#define __HAL_RCC_CEC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CECLPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) +#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) +#define __HAL_RCC_SAI2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI2LPEN)) +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) + +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) +#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) +#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) +#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) +#define __HAL_RCC_SAI2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI2LPEN)) +/** + * @} + */ + +#endif /* STM32F446xx */ +/*----------------------------------------------------------------------------*/ + +/*-------STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx-------*/ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) +#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) +#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) + +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) +#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable + * @brief Enable or disable the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F423xx) +#define __HAL_RCC_AES_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_AES_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_AESEN)) +#endif /* STM32F423xx */ + +#define __HAL_RCC_RNG_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) + +#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ + __HAL_RCC_SYSCFG_CLK_ENABLE();\ + }while(0U) + +#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F423xx) +#define __HAL_RCC_AES_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) != RESET) +#define __HAL_RCC_AES_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) == RESET) +#endif /* STM32F423xx */ + +#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) +#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) + +#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) +#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable + * @brief Enables or disables the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ + UNUSED(tmpreg); \ + } while(0U) + +#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) +#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) +#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) + +#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) +#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ + +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable + * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_USART3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ + UNUSED(tmpreg); \ + } while(0U) + +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DAC_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART7_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) +#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) +#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) +#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) +#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) +#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) +#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) +#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) +#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) +#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) +#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) +#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN3EN)) +#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) +#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) +#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) +#endif /* STM32F413xx || STM32F423xx */ + +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) +#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) +#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) +#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) +#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) +#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) +#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) +#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) +#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) +#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) +#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) +#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN))!= RESET) +#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) != RESET) +#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) +#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) +#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) +#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) +#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) +#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) +#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) +#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) +#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) +#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) +#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) +#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) +#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) +#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) +#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) +#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) == RESET) +#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) +#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) +#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ +/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable + * @brief Enable or disable the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_UART10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ + UNUSED(tmpreg); \ + } while(0U) +#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ + UNUSED(tmpreg); \ + } while(0U) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_CLK_ENABLE() do { \ + __IO uint32_t tmpreg = 0x00U; \ + SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ + UNUSED(tmpreg); \ + } while(0U) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART9EN)) +#define __HAL_RCC_UART10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART10EN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) +#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) +#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) +#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) +#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM1EN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM2EN)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status + * @brief Get the enable or disable status of the APB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @{ + */ +#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) != RESET) +#define __HAL_RCC_UART10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) +#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) +#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) +#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) +#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) != RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) != RESET) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) == RESET) +#define __HAL_RCC_UART10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) +#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) +#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) +#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) +#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) == RESET) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) == RESET) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset + * @brief Force or release AHB1 peripheral reset. + * @{ + */ +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) + +#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) +#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) +#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) +#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) +#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ +#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset + * @brief Force or release AHB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) + +#if defined(STM32F423xx) +#define __HAL_RCC_AES_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_AESRST)) +#define __HAL_RCC_AES_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_AESRST)) +#endif /* STM32F423xx */ + +#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) +#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) + +#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) +#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset + * @brief Force or release AHB3 peripheral reset. + * @{ + */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) +#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) + +#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) +#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) + +#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) +#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ +#if defined(STM32F412Cx) +#define __HAL_RCC_AHB3_FORCE_RESET() +#define __HAL_RCC_AHB3_RELEASE_RESET() + +#define __HAL_RCC_FSMC_FORCE_RESET() +#define __HAL_RCC_QSPI_FORCE_RESET() + +#define __HAL_RCC_FSMC_RELEASE_RESET() +#define __HAL_RCC_QSPI_RELEASE_RESET() +#endif /* STM32F412Cx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset + * @brief Force or release APB1 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) +#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN3RST)) +#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) +#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) +#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) +#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) +#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) +#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) +#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) +#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) +#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) +#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) +#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) +#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) +#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) +#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN3RST)) +#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) +#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) +#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset + * @brief Force or release APB2 peripheral reset. + * @{ + */ +#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART9RST)) +#define __HAL_RCC_UART10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART10RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM1RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM2RST)) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART9RST)) +#define __HAL_RCC_UART10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART10RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) +#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) +#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) +#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM1RST)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM2RST)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) +#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) +#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) +#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) +#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) +#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) +#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#if defined(STM32F423xx) +#define __HAL_RCC_AES_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_AESLPEN)) +#define __HAL_RCC_AES_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_AESLPEN)) +#endif /* STM32F423xx */ + +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) +#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) + +#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) +#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) +/** + * @} + */ + +/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable + * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) +#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) + +#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) +#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ + +/** + * @} + */ + +/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN3LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) +#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) +#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) +#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) +#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) +#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) +#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) +#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) +#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) +#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) +#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) +#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) +#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) +#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) +#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_CAN3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN3LPEN)) +#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) +#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) +#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ + +/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable + * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @{ + */ +#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART9LPEN)) +#define __HAL_RCC_UART10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART10LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM1LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM2LPEN)) +#endif /* STM32F413xx || STM32F423xx */ + +#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_UART9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART9LPEN)) +#define __HAL_RCC_UART10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART10LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) +#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) +#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) +#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) +#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +#define __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM1LPEN)) +#if defined(STM32F413xx) || defined(STM32F423xx) +#define __HAL_RCC_DFSDM2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM2LPEN)) +#endif /* STM32F413xx || STM32F423xx */ +/** + * @} + */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------------------- PLL Configuration --------------------------*/ +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @brief Macro to configure the main PLL clock source, multiplication and division factors. + * @note This function must be used only when the main PLL is disabled. + * @param __RCC_PLLSource__ specifies the PLL entry clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry + * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry + * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. + * @param __PLLM__ specifies the division factor for PLL VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 2 MHz to limit PLL jitter. + * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLN parameter correctly to ensure that the VCO + * output frequency is between 100 and 432 MHz. + * + * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) + * This parameter must be a number in the range {2, 4, 6, or 8}. + * + * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * @note If the USB OTG FS is used in your application, you have to set the + * PLLQ parameter correctly to have 48 MHz clock for the USB. However, + * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work + * correctly. + * + * @param __PLLR__ PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note This parameter is only available in STM32F446xx/STM32F469xx/STM32F479xx/ + STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. + * + */ +#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__,__PLLR__) \ + (RCC->PLLCFGR = ((__RCC_PLLSource__) | (__PLLM__) | \ + ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ + ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ + ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos) | \ + ((__PLLR__) << RCC_PLLCFGR_PLLR_Pos))) +#else +/** @brief Macro to configure the main PLL clock source, multiplication and division factors. + * @note This function must be used only when the main PLL is disabled. + * @param __RCC_PLLSource__ specifies the PLL entry clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry + * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry + * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. + * @param __PLLM__ specifies the division factor for PLL VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 2 MHz to limit PLL jitter. + * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock + * This parameter must be a number between Min_Data = 50 and Max_Data = 432 + * Except for STM32F411xE devices where Min_Data = 192. + * @note You have to set the PLLN parameter correctly to ensure that the VCO + * output frequency is between 100 and 432 MHz, Except for STM32F411xE devices + * where frequency is between 192 and 432 MHz. + * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) + * This parameter must be a number in the range {2, 4, 6, or 8}. + * + * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * @note If the USB OTG FS is used in your application, you have to set the + * PLLQ parameter correctly to have 48 MHz clock for the USB. However, + * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work + * correctly. + * + */ +#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__) \ + (RCC->PLLCFGR = (0x20000000U | (__RCC_PLLSource__) | (__PLLM__)| \ + ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ + ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ + ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos))) + #endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +/*----------------------------------------------------------------------------*/ + +/*----------------------------PLLI2S Configuration ---------------------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + +/** @brief Macros to enable or disable the PLLI2S. + * @note The PLLI2S is disabled by hardware when entering STOP and STANDBY modes. + */ +#define __HAL_RCC_PLLI2S_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = ENABLE) +#define __HAL_RCC_PLLI2S_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = DISABLE) + +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || + STM32F412Rx || STM32F412Cx */ +#if defined(STM32F446xx) +/** @brief Macro to configure the PLLI2S clock multiplication and division factors . + * @note This macro must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * HAL_RCC_ClockConfig() API). + * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 1 MHz to limit PLLI2S jitter. + * + * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLI2SP__ specifies division factor for SPDIFRX Clock. + * This parameter must be a number in the range {2, 4, 6, or 8}. + * @note the PLLI2SP parameter is only available with STM32F446xx Devices + * + * @param __PLLI2SR__ specifies the division factor for I2S clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + * + * @param __PLLI2SQ__ specifies the division factor for SAI clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + */ +#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SP__, __PLLI2SQ__, __PLLI2SR__) \ + (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ + ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ + ((((__PLLI2SP__) >> 1U) -1U) << RCC_PLLI2SCFGR_PLLI2SP_Pos) |\ + ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ + ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) +#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +/** @brief Macro to configure the PLLI2S clock multiplication and division factors . + * @note This macro must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * HAL_RCC_ClockConfig() API). + * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 1 MHz to limit PLLI2S jitter. + * + * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLI2SR__ specifies the division factor for I2S clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + * + * @param __PLLI2SQ__ specifies the division factor for SAI clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + */ +#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) \ + (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ + ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ + ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ + ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) +#else +/** @brief Macro to configure the PLLI2S clock multiplication and division factors . + * @note This macro must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * HAL_RCC_ClockConfig() API). + * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLI2SR__ specifies the division factor for I2S clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + * + */ +#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SN__, __PLLI2SR__) \ + (RCC->PLLI2SCFGR = (((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ + ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) +#endif /* STM32F446xx */ + +#if defined(STM32F411xE) +/** @brief Macro to configure the PLLI2S clock multiplication and division factors . + * @note This macro must be used only when the PLLI2S is disabled. + * @note This macro must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * HAL_RCC_ClockConfig() API). + * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note The PLLI2SM parameter is only used with STM32F411xE/STM32F410xx Devices + * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 2 MHz to limit PLLI2S jitter. + * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock + * This parameter must be a number between Min_Data = 192 and Max_Data = 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 192 and Max_Data = 432 MHz. + * @param __PLLI2SR__ specifies the division factor for I2S clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + */ +#define __HAL_RCC_PLLI2S_I2SCLK_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ + ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ + ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) +#endif /* STM32F411xE */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macro used by the SAI HAL driver to configure the PLLI2S clock multiplication and division factors. + * @note This macro must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * HAL_RCC_ClockConfig() API) + * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock. + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * @param __PLLI2SQ__ specifies the division factor for SAI1 clock. + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * @note the PLLI2SQ parameter is only available with STM32F427xx/437xx/429xx/439xx/469xx/479xx + * Devices and can be configured using the __HAL_RCC_PLLI2S_PLLSAICLK_CONFIG() macro + * @param __PLLI2SR__ specifies the division factor for I2S clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + */ +#define __HAL_RCC_PLLI2S_SAICLK_CONFIG(__PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SN__) << 6U) |\ + ((__PLLI2SQ__) << 24U) |\ + ((__PLLI2SR__) << 28U)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------------------ PLLSAI Configuration ------------------------*/ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macros to Enable or Disable the PLLISAI. + * @note The PLLSAI is only available with STM32F429x/439x Devices. + * @note The PLLSAI is disabled by hardware when entering STOP and STANDBY modes. + */ +#define __HAL_RCC_PLLSAI_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = ENABLE) +#define __HAL_RCC_PLLSAI_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = DISABLE) + +#if defined(STM32F446xx) +/** @brief Macro to configure the PLLSAI clock multiplication and division factors. + * + * @param __PLLSAIM__ specifies the division factor for PLLSAI VCO input clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 63. + * @note You have to set the PLLSAIM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 1 MHz to limit PLLI2S jitter. + * @note The PLLSAIM parameter is only used with STM32F446xx Devices + * + * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLSAIP__ specifies division factor for OTG FS, SDIO and RNG clocks. + * This parameter must be a number in the range {2, 4, 6, or 8}. + * @note the PLLSAIP parameter is only available with STM32F446xx Devices + * + * @param __PLLSAIQ__ specifies the division factor for SAI clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * + * @param __PLLSAIR__ specifies the division factor for LTDC clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices + */ +#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIM__, __PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ + (RCC->PLLSAICFGR = ((__PLLSAIM__) | \ + ((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ + ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) | \ + ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos))) +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macro to configure the PLLSAI clock multiplication and division factors. + * + * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLSAIP__ specifies division factor for SDIO and CLK48 clocks. + * This parameter must be a number in the range {2, 4, 6, or 8}. + * + * @param __PLLSAIQ__ specifies the division factor for SAI clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * + * @param __PLLSAIR__ specifies the division factor for LTDC clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + */ +#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ + (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) |\ + ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) |\ + ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) |\ + ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +/** @brief Macro to configure the PLLSAI clock multiplication and division factors. + * + * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. + * This parameter must be a number between Min_Data = 50 and Max_Data = 432. + * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO + * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. + * + * @param __PLLSAIQ__ specifies the division factor for SAI clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 15. + * + * @param __PLLSAIR__ specifies the division factor for LTDC clock + * This parameter must be a number between Min_Data = 2 and Max_Data = 7. + * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices + */ +#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIQ__, __PLLSAIR__) \ + (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ + ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) | \ + ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------- PLLSAI/PLLI2S Dividers Configuration -------------------*/ +#if defined(STM32F413xx) || defined(STM32F423xx) +/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. + * @note This function must be called before enabling the PLLI2S. + * @param __PLLI2SDivR__ specifies the PLLI2S division factor for SAI1 clock. + * This parameter must be a number between 1 and 32. + * SAI1 clock frequency = f(PLLI2SR) / __PLLI2SDivR__ + */ +#define __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(__PLLI2SDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, (__PLLI2SDivR__)-1U)) + +/** @brief Macro to configure the SAI clock Divider coming from PLL. + * @param __PLLDivR__ specifies the PLL division factor for SAI1 clock. + * This parameter must be a number between 1 and 32. + * SAI1 clock frequency = f(PLLR) / __PLLDivR__ + */ +#define __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(__PLLDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, ((__PLLDivR__)-1U)<<8U)) +#endif /* STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. + * @note This function must be called before enabling the PLLI2S. + * @param __PLLI2SDivQ__ specifies the PLLI2S division factor for SAI1 clock. + * This parameter must be a number between 1 and 32. + * SAI1 clock frequency = f(PLLI2SQ) / __PLLI2SDivQ__ + */ +#define __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(__PLLI2SDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, (__PLLI2SDivQ__)-1U)) + +/** @brief Macro to configure the SAI clock Divider coming from PLLSAI. + * @note This function must be called before enabling the PLLSAI. + * @param __PLLSAIDivQ__ specifies the PLLSAI division factor for SAI1 clock . + * This parameter must be a number between Min_Data = 1 and Max_Data = 32. + * SAI1 clock frequency = f(PLLSAIQ) / __PLLSAIDivQ__ + */ +#define __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(__PLLSAIDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, ((__PLLSAIDivQ__)-1U)<<8U)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Macro to configure the LTDC clock Divider coming from PLLSAI. + * + * @note The LTDC peripheral is only available with STM32F427/437/429/439/469/479xx Devices. + * @note This function must be called before enabling the PLLSAI. + * @param __PLLSAIDivR__ specifies the PLLSAI division factor for LTDC clock . + * This parameter must be a number between Min_Data = 2 and Max_Data = 16. + * LTDC clock frequency = f(PLLSAIR) / __PLLSAIDivR__ + */ +#define __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(__PLLSAIDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, (__PLLSAIDivR__))) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +/*----------------------------------------------------------------------------*/ + +/*------------------------- Peripheral Clock selection -----------------------*/ +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) ||\ + defined(STM32F479xx) +/** @brief Macro to configure the I2S clock source (I2SCLK). + * @note This function must be called before enabling the I2S APB clock. + * @param __SOURCE__ specifies the I2S clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. + * @arg RCC_I2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin + * used as I2S clock source. + */ +#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_CFGR_I2SSRC_BB = (__SOURCE__)) + + +/** @brief Macro to get the I2S clock source (I2SCLK). + * @retval The clock source can be one of the following values: + * @arg @ref RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. + * @arg @ref RCC_I2SCLKSOURCE_EXT External clock mapped on the I2S_CKIN pin + * used as I2S clock source + */ +#define __HAL_RCC_GET_I2S_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_I2SSRC))) +#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/** @brief Macro to configure SAI1BlockA clock source selection. + * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. + * @note This function must be called before enabling PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI Block A clock source. + * This parameter can be one of the following values: + * @arg RCC_SAIACLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used + * as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used + * as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin + * used as SAI1 Block A clock. + */ +#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) + +/** @brief Macro to configure SAI1BlockB clock source selection. + * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. + * @note This function must be called before enabling PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI Block B clock source. + * This parameter can be one of the following values: + * @arg RCC_SAIBCLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used + * as SAI1 Block B clock. + * @arg RCC_SAIBCLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used + * as SAI1 Block B clock. + * @arg RCC_SAIBCLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin + * used as SAI1 Block B clock. + */ +#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F446xx) +/** @brief Macro to configure SAI1 clock source selection. + * @note This configuration is only available with STM32F446xx Devices. + * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI1 clock source. + * This parameter can be one of the following values: + * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. + */ +#define __HAL_RCC_SAI1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC, (__SOURCE__))) + +/** @brief Macro to Get SAI1 clock source selection. + * @note This configuration is only available with STM32F446xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. + * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. + */ +#define __HAL_RCC_GET_SAI1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC)) + +/** @brief Macro to configure SAI2 clock source selection. + * @note This configuration is only available with STM32F446xx Devices. + * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI2 clock source. + * This parameter can be one of the following values: + * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. + */ +#define __HAL_RCC_SAI2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC, (__SOURCE__))) + +/** @brief Macro to Get SAI2 clock source selection. + * @note This configuration is only available with STM32F446xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. + * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. + */ +#define __HAL_RCC_GET_SAI2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC)) + +/** @brief Macro to configure I2S APB1 clock source selection. + * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. + * @param __SOURCE__ specifies the I2S APB1 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. + * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. + * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. + * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) + +/** @brief Macro to Get I2S APB1 clock source selection. + * @retval The clock source can be one of the following values: + * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. + * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. + * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. + * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) + +/** @brief Macro to configure I2S APB2 clock source selection. + * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. + * @param __SOURCE__ specifies the SAI Block A clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. + * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. + * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. + * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) + +/** @brief Macro to Get I2S APB2 clock source selection. + * @retval The clock source can be one of the following values: + * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. + * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. + * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. + * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) + +/** @brief Macro to configure the CEC clock. + * @param __SOURCE__ specifies the CEC clock source. + * This parameter can be one of the following values: + * @arg RCC_CECCLKSOURCE_HSI: HSI selected as CEC clock + * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock + */ +#define __HAL_RCC_CEC_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the CEC clock. + * @retval The clock source can be one of the following values: + * @arg RCC_CECCLKSOURCE_HSI488: HSI selected as CEC clock + * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock + */ +#define __HAL_RCC_GET_CEC_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL)) + +/** @brief Macro to configure the FMPI2C1 clock. + * @param __SOURCE__ specifies the FMPI2C1 clock source. + * This parameter can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the FMPI2C1 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) + +/** @brief Macro to configure the CLK48 clock. + * @param __SOURCE__ specifies the CLK48 clock source. + * This parameter can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. + */ +#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the CLK48 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. + */ +#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) + +/** @brief Macro to configure the SDIO clock. + * @param __SOURCE__ specifies the SDIO clock source. + * This parameter can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the SDIO clock. + * @retval The clock source can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) + +/** @brief Macro to configure the SPDIFRX clock. + * @param __SOURCE__ specifies the SPDIFRX clock source. + * This parameter can be one of the following values: + * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. + * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. + */ +#define __HAL_RCC_SPDIFRX_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the SPDIFRX clock. + * @retval The clock source can be one of the following values: + * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. + * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. + */ +#define __HAL_RCC_GET_SPDIFRX_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL)) +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) + +/** @brief Macro to configure the CLK48 clock. + * @param __SOURCE__ specifies the CLK48 clock source. + * This parameter can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. + */ +#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the CLK48 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. + */ +#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL)) + +/** @brief Macro to configure the SDIO clock. + * @param __SOURCE__ specifies the SDIO clock source. + * This parameter can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the SDIO clock. + * @retval The clock source can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL)) + +/** @brief Macro to configure the DSI clock. + * @param __SOURCE__ specifies the DSI clock source. + * This parameter can be one of the following values: + * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. + * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. + */ +#define __HAL_RCC_DSI_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the DSI clock. + * @retval The clock source can be one of the following values: + * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. + * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. + */ +#define __HAL_RCC_GET_DSI_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL)) + +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) + /** @brief Macro to configure the DFSDM1 clock. + * @param __DFSDM1_CLKSOURCE__ specifies the DFSDM1 clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. + * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. + * @retval None + */ +#define __HAL_RCC_DFSDM1_CONFIG(__DFSDM1_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM1_CLKSOURCE__)) + +/** @brief Macro to get the DFSDM1 clock source. + * @retval The clock source can be one of the following values: + * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. + * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. + */ +#define __HAL_RCC_GET_DFSDM1_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) + +/** @brief Macro to configure DFSDM1 Audio clock source selection. + * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ + STM32F413xx/STM32F423xx Devices. + * @param __SOURCE__ specifies the DFSDM1 Audio clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock + */ +#define __HAL_RCC_DFSDM1AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL, (__SOURCE__))) + +/** @brief Macro to Get DFSDM1 Audio clock source selection. + * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ + STM32F413xx/STM32F423xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock + */ +#define __HAL_RCC_GET_DFSDM1AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL)) + +#if defined(STM32F413xx) || defined(STM32F423xx) + /** @brief Macro to configure the DFSDM2 clock. + * @param __DFSDM2_CLKSOURCE__ specifies the DFSDM1 clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. + * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. + * @retval None + */ +#define __HAL_RCC_DFSDM2_CONFIG(__DFSDM2_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM2_CLKSOURCE__)) + +/** @brief Macro to get the DFSDM2 clock source. + * @retval The clock source can be one of the following values: + * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. + * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. + */ +#define __HAL_RCC_GET_DFSDM2_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) + +/** @brief Macro to configure DFSDM1 Audio clock source selection. + * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. + * @param __SOURCE__ specifies the DFSDM2 Audio clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock + * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock + */ +#define __HAL_RCC_DFSDM2AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL, (__SOURCE__))) + +/** @brief Macro to Get DFSDM2 Audio clock source selection. + * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock + * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock + */ +#define __HAL_RCC_GET_DFSDM2AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL)) + +/** @brief Macro to configure SAI1BlockA clock source selection. + * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. + * @note This function must be called before enabling PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI Block A clock source. + * This parameter can be one of the following values: + * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) + +/** @brief Macro to Get SAI1 BlockA clock source selection. + * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. + * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_SAI_BLOCKA_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC)) + +/** @brief Macro to configure SAI1 BlockB clock source selection. + * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. + * @note This function must be called before enabling PLLSAI, PLLI2S and + * the SAI clock. + * @param __SOURCE__ specifies the SAI Block B clock source. + * This parameter can be one of the following values: + * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) + +/** @brief Macro to Get SAI1 BlockB clock source selection. + * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. + * @retval The clock source can be one of the following values: + * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. + * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_SAI_BLOCKB_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC)) + +/** @brief Macro to configure the LPTIM1 clock. + * @param __SOURCE__ specifies the LPTIM1 clock source. + * This parameter can be one of the following values: + * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock + */ +#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the LPTIM1 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock + */ +#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) +#endif /* STM32F413xx || STM32F423xx */ + +/** @brief Macro to configure I2S APB1 clock source selection. + * @param __SOURCE__ specifies the I2S APB1 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. + * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. + * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) + +/** @brief Macro to Get I2S APB1 clock source selection. + * @retval The clock source can be one of the following values: + * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. + * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. + * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) + +/** @brief Macro to configure I2S APB2 clock source selection. + * @param __SOURCE__ specifies the I2S APB2 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. + * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. + * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) + +/** @brief Macro to Get I2S APB2 clock source selection. + * @retval The clock source can be one of the following values: + * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. + * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. + * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + */ +#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) + +/** @brief Macro to configure the PLL I2S clock source (PLLI2SCLK). + * @note This macro must be called before enabling the I2S APB clock. + * @param __SOURCE__ specifies the I2S clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLI2SCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. + * @arg RCC_PLLI2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin + * used as I2S clock source. + */ +#define __HAL_RCC_PLL_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_PLLI2SCFGR_PLLI2SSRC_BB = (__SOURCE__)) + +/** @brief Macro to configure the FMPI2C1 clock. + * @param __SOURCE__ specifies the FMPI2C1 clock source. + * This parameter can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the FMPI2C1 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) + +/** @brief Macro to configure the CLK48 clock. + * @param __SOURCE__ specifies the CLK48 clock source. + * This parameter can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock. + */ +#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the CLK48 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. + * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock + */ +#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) + +/** @brief Macro to configure the SDIO clock. + * @param __SOURCE__ specifies the SDIO clock source. + * This parameter can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the SDIO clock. + * @retval The clock source can be one of the following values: + * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. + * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. + */ +#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) + +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** @brief Macro to configure I2S clock source selection. + * @param __SOURCE__ specifies the I2S clock source. + * This parameter can be one of the following values: + * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. + * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. + */ +#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC, (__SOURCE__))) + +/** @brief Macro to Get I2S clock source selection. + * @retval The clock source can be one of the following values: + * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. + * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. + * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. + */ +#define __HAL_RCC_GET_I2S_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC)) + +/** @brief Macro to configure the FMPI2C1 clock. + * @param __SOURCE__ specifies the FMPI2C1 clock source. + * This parameter can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the FMPI2C1 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock + * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock + */ +#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) + +/** @brief Macro to configure the LPTIM1 clock. + * @param __SOURCE__ specifies the LPTIM1 clock source. + * This parameter can be one of the following values: + * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock + */ +#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) + +/** @brief Macro to Get the LPTIM1 clock. + * @retval The clock source can be one of the following values: + * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock + * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock + */ +#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @brief Macro to configure the Timers clocks prescalers + * @note This feature is only available with STM32F429x/439x Devices. + * @param __PRESC__ specifies the Timers clocks prescalers selection + * This parameter can be one of the following values: + * @arg RCC_TIMPRES_DESACTIVATED: The Timers kernels clocks prescaler is + * equal to HPRE if PPREx is corresponding to division by 1 or 2, + * else it is equal to [(HPRE * PPREx) / 2] if PPREx is corresponding to + * division by 4 or more. + * @arg RCC_TIMPRES_ACTIVATED: The Timers kernels clocks prescaler is + * equal to HPRE if PPREx is corresponding to division by 1, 2 or 4, + * else it is equal to [(HPRE * PPREx) / 4] if PPREx is corresponding + * to division by 8 or more. + */ +#define __HAL_RCC_TIMCLKPRESCALER(__PRESC__) (*(__IO uint32_t *) RCC_DCKCFGR_TIMPRE_BB = (__PRESC__)) + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx) || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE ||\ + STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx ||\ + STM32F423xx */ + +/*----------------------------------------------------------------------------*/ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @brief Enable PLLSAI_RDY interrupt. + */ +#define __HAL_RCC_PLLSAI_ENABLE_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYIE)) + +/** @brief Disable PLLSAI_RDY interrupt. + */ +#define __HAL_RCC_PLLSAI_DISABLE_IT() (RCC->CIR &= ~(RCC_CIR_PLLSAIRDYIE)) + +/** @brief Clear the PLLSAI RDY interrupt pending bits. + */ +#define __HAL_RCC_PLLSAI_CLEAR_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYF)) + +/** @brief Check the PLLSAI RDY interrupt has occurred or not. + * @retval The new state (TRUE or FALSE). + */ +#define __HAL_RCC_PLLSAI_GET_IT() ((RCC->CIR & (RCC_CIR_PLLSAIRDYIE)) == (RCC_CIR_PLLSAIRDYIE)) + +/** @brief Check PLLSAI RDY flag is set or not. + * @retval The new state (TRUE or FALSE). + */ +#define __HAL_RCC_PLLSAI_GET_FLAG() ((RCC->CR & (RCC_CR_PLLSAIRDY)) == (RCC_CR_PLLSAIRDY)) + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** @brief Macros to enable or disable the RCC MCO1 feature. + */ +#define __HAL_RCC_MCO1_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = ENABLE) +#define __HAL_RCC_MCO1_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = DISABLE) + +/** @brief Macros to enable or disable the RCC MCO2 feature. + */ +#define __HAL_RCC_MCO2_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = ENABLE) +#define __HAL_RCC_MCO2_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = DISABLE) + +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup RCCEx_Exported_Functions + * @{ + */ + +/** @addtogroup RCCEx_Exported_Functions_Group1 + * @{ + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); + +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk); + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +void HAL_RCCEx_SelectLSEMode(uint8_t Mode); +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +#if defined(RCC_PLLI2S_SUPPORT) +HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit); +HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void); +#endif /* RCC_PLLI2S_SUPPORT */ +#if defined(RCC_PLLSAI_SUPPORT) +HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit); +HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void); +#endif /* RCC_PLLSAI_SUPPORT */ +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup RCCEx_Private_Constants RCCEx Private Constants + * @{ + */ + +/** @defgroup RCCEx_BitAddress_AliasRegion RCC BitAddress AliasRegion + * @brief RCC registers bit address in the alias region + * @{ + */ +/* --- CR Register ---*/ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/* Alias word address of PLLSAION bit */ +#define RCC_PLLSAION_BIT_NUMBER 0x1CU +#define RCC_CR_PLLSAION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLSAION_BIT_NUMBER * 4U)) + +#define PLLSAI_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/* Alias word address of PLLI2SON bit */ +#define RCC_PLLI2SON_BIT_NUMBER 0x1AU +#define RCC_CR_PLLI2SON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLI2SON_BIT_NUMBER * 4U)) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || + STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +/* --- DCKCFGR Register ---*/ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ + defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/* Alias word address of TIMPRE bit */ +#define RCC_DCKCFGR_OFFSET (RCC_OFFSET + 0x8CU) +#define RCC_TIMPRE_BIT_NUMBER 0x18U +#define RCC_DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (RCC_DCKCFGR_OFFSET * 32U) + (RCC_TIMPRE_BIT_NUMBER * 4U)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F410xx || STM32F401xC ||\ + STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +/* --- CFGR Register ---*/ +#define RCC_CFGR_OFFSET (RCC_OFFSET + 0x08U) +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) +/* Alias word address of I2SSRC bit */ +#define RCC_I2SSRC_BIT_NUMBER 0x17U +#define RCC_CFGR_I2SSRC_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_I2SSRC_BIT_NUMBER * 4U)) + +#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +/* --- PLLI2SCFGR Register ---*/ +#define RCC_PLLI2SCFGR_OFFSET (RCC_OFFSET + 0x84U) +/* Alias word address of PLLI2SSRC bit */ +#define RCC_PLLI2SSRC_BIT_NUMBER 0x16U +#define RCC_PLLI2SCFGR_PLLI2SSRC_BB (PERIPH_BB_BASE + (RCC_PLLI2SCFGR_OFFSET * 32U) + (RCC_PLLI2SSRC_BIT_NUMBER * 4U)) + +#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx | STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/* Alias word address of MCO1EN bit */ +#define RCC_MCO1EN_BIT_NUMBER 0x8U +#define RCC_CFGR_MCO1EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO1EN_BIT_NUMBER * 4U)) + +/* Alias word address of MCO2EN bit */ +#define RCC_MCO2EN_BIT_NUMBER 0x9U +#define RCC_CFGR_MCO2EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO2EN_BIT_NUMBER * 4U)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#define PLL_TIMEOUT_VALUE 2U /* 2 ms */ +/** + * @} + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup RCCEx_Private_Macros RCCEx Private Macros + * @{ + */ +/** @defgroup RCCEx_IS_RCC_Definitions RCC Private macros to check input parameters + * @{ + */ +#define IS_RCC_PLLN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) +#define IS_RCC_PLLI2SN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000007FU)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000007U)) +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000000FU)) +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000001FU)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F446xx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000FFFU)) +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000001FFU)) +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000003FFU)) +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + +#if defined(STM32F413xx) || defined(STM32F423xx) +#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00007FFFU)) +#endif /* STM32F413xx || STM32F423xx */ + +#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) + +#define IS_RCC_PLLSAIN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) + +#define IS_RCC_PLLSAIQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) + +#define IS_RCC_PLLSAIR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#define IS_RCC_PLLSAI_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) + +#define IS_RCC_PLLI2S_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) + +#define IS_RCC_PLLSAI_DIVR_VALUE(VALUE) (((VALUE) == RCC_PLLSAIDIVR_2) ||\ + ((VALUE) == RCC_PLLSAIDIVR_4) ||\ + ((VALUE) == RCC_PLLSAIDIVR_8) ||\ + ((VALUE) == RCC_PLLSAIDIVR_16)) +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +#define IS_RCC_PLLI2SM_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 63U)) + +#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ + ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) +#endif /* STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ + ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) + +#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) + +#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) + +#define IS_RCC_I2SAPBCLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F446xx) +#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == RCC_PLLI2SP_DIV2) ||\ + ((VALUE) == RCC_PLLI2SP_DIV4) ||\ + ((VALUE) == RCC_PLLI2SP_DIV6) ||\ + ((VALUE) == RCC_PLLI2SP_DIV8)) + +#define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63U) + +#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ + ((VALUE) == RCC_PLLSAIP_DIV4) ||\ + ((VALUE) == RCC_PLLSAIP_DIV6) ||\ + ((VALUE) == RCC_PLLSAIP_DIV8)) + +#define IS_RCC_SAI1CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI1CLKSOURCE_PLLSAI) ||\ + ((SOURCE) == RCC_SAI1CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_SAI1CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_SAI1CLKSOURCE_EXT)) + +#define IS_RCC_SAI2CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI2CLKSOURCE_PLLSAI) ||\ + ((SOURCE) == RCC_SAI2CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_SAI2CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_SAI2CLKSOURCE_PLLSRC)) + +#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) + + #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) + +#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) + +#define IS_RCC_CECCLKSOURCE(SOURCE) (((SOURCE) == RCC_CECCLKSOURCE_HSI) ||\ + ((SOURCE) == RCC_CECCLKSOURCE_LSE)) + +#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ + ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) + +#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ + ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) + +#define IS_RCC_SPDIFRXCLKSOURCE(SOURCE) (((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ + ((VALUE) == RCC_PLLSAIP_DIV4) ||\ + ((VALUE) == RCC_PLLSAIP_DIV6) ||\ + ((VALUE) == RCC_PLLSAIP_DIV8)) + +#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ + ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) + +#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ + ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) + +#define IS_RCC_DSIBYTELANECLKSOURCE(SOURCE) (((SOURCE) == RCC_DSICLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_DSICLKSOURCE_DSIPHY)) + +#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ + ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) + +#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) + +#define IS_RCC_PLLI2SCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_PLLI2SCLKSOURCE_PLLSRC) || \ + ((__SOURCE__) == RCC_PLLI2SCLKSOURCE_EXT)) + +#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) + + #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) + +#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ + ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) + +#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ + ((SOURCE) == RCC_CLK48CLKSOURCE_PLLI2SQ)) + +#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ + ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) + +#define IS_RCC_DFSDM1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1CLKSOURCE_PCLK2) || \ + ((__SOURCE__) == RCC_DFSDM1CLKSOURCE_SYSCLK)) + +#define IS_RCC_DFSDM1AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S1) || \ + ((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S2)) + +#if defined(STM32F413xx) || defined(STM32F423xx) +#define IS_RCC_DFSDM2CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2CLKSOURCE_PCLK2) || \ + ((__SOURCE__) == RCC_DFSDM2CLKSOURCE_SYSCLK)) + +#define IS_RCC_DFSDM2AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S1) || \ + ((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S2)) + +#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) + +#define IS_RCC_SAIACLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIACLKSOURCE_PLLI2SR) ||\ + ((SOURCE) == RCC_SAIACLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_SAIACLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_SAIACLKSOURCE_PLLSRC)) + +#define IS_RCC_SAIBCLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIBCLKSOURCE_PLLI2SR) ||\ + ((SOURCE) == RCC_SAIBCLKSOURCE_EXT) ||\ + ((SOURCE) == RCC_SAIBCLKSOURCE_PLLR) ||\ + ((SOURCE) == RCC_SAIBCLKSOURCE_PLLSRC)) + +#define IS_RCC_PLL_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) + +#define IS_RCC_PLLI2S_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) + +#endif /* STM32F413xx || STM32F423xx */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) + +#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_PLLI2SCLK)|| \ + ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) + +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || + STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || \ + STM32F412Rx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_I2SCLK)|| \ + ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_RCC_EX_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h index d7997a3..9e1867b 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h @@ -1,729 +1,729 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spi.h - * @author MCD Application Team - * @brief Header file of SPI HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SPI_H -#define STM32F4xx_HAL_SPI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SPI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SPI_Exported_Types SPI Exported Types - * @{ - */ - -/** - * @brief SPI Configuration Structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the SPI operating mode. - This parameter can be a value of @ref SPI_Mode */ - - uint32_t Direction; /*!< Specifies the SPI bidirectional mode state. - This parameter can be a value of @ref SPI_Direction */ - - uint32_t DataSize; /*!< Specifies the SPI data size. - This parameter can be a value of @ref SPI_Data_Size */ - - uint32_t CLKPolarity; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_Clock_Phase */ - - uint32_t NSS; /*!< Specifies whether the NSS signal is managed by - hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_Slave_Select_management */ - - uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be - used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_BaudRate_Prescaler - @note The communication clock is derived from the master - clock. The slave clock does not need to be set. */ - - uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_MSB_LSB_transmission */ - - uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not. - This parameter can be a value of @ref SPI_TI_mode */ - - uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. - This parameter can be a value of @ref SPI_CRC_Calculation */ - - uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. - This parameter must be an odd number between Min_Data = 1 and Max_Data = 65535 */ -} SPI_InitTypeDef; - -/** - * @brief HAL SPI State structure definition - */ -typedef enum -{ - HAL_SPI_STATE_RESET = 0x00U, /*!< Peripheral not Initialized */ - HAL_SPI_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_SPI_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_SPI_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ - HAL_SPI_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ - HAL_SPI_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ - HAL_SPI_STATE_ERROR = 0x06U, /*!< SPI error state */ - HAL_SPI_STATE_ABORT = 0x07U /*!< SPI abort is ongoing */ -} HAL_SPI_StateTypeDef; - -/** - * @brief SPI handle Structure definition - */ -typedef struct __SPI_HandleTypeDef -{ - SPI_TypeDef *Instance; /*!< SPI registers base address */ - - SPI_InitTypeDef Init; /*!< SPI communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SPI Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< SPI Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< SPI Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SPI Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< SPI Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< SPI Rx Transfer Counter */ - - void (*RxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Rx ISR */ - - void (*TxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Tx ISR */ - - DMA_HandleTypeDef *hdmatx; /*!< SPI Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SPI Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_SPI_StateTypeDef State; /*!< SPI communication state */ - - __IO uint32_t ErrorCode; /*!< SPI Error code */ - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Completed callback */ - void (* RxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Completed callback */ - void (* TxRxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Completed callback */ - void (* TxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Half Completed callback */ - void (* RxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Half Completed callback */ - void (* TxRxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Half Completed callback */ - void (* ErrorCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Error callback */ - void (* AbortCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Abort callback */ - void (* MspInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp Init callback */ - void (* MspDeInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp DeInit callback */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} SPI_HandleTypeDef; - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL SPI Callback ID enumeration definition - */ -typedef enum -{ - HAL_SPI_TX_COMPLETE_CB_ID = 0x00U, /*!< SPI Tx Completed callback ID */ - HAL_SPI_RX_COMPLETE_CB_ID = 0x01U, /*!< SPI Rx Completed callback ID */ - HAL_SPI_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< SPI TxRx Completed callback ID */ - HAL_SPI_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< SPI Tx Half Completed callback ID */ - HAL_SPI_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< SPI Rx Half Completed callback ID */ - HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< SPI TxRx Half Completed callback ID */ - HAL_SPI_ERROR_CB_ID = 0x06U, /*!< SPI Error callback ID */ - HAL_SPI_ABORT_CB_ID = 0x07U, /*!< SPI Abort callback ID */ - HAL_SPI_MSPINIT_CB_ID = 0x08U, /*!< SPI Msp Init callback ID */ - HAL_SPI_MSPDEINIT_CB_ID = 0x09U /*!< SPI Msp DeInit callback ID */ - -} HAL_SPI_CallbackIDTypeDef; - -/** - * @brief HAL SPI Callback pointer definition - */ -typedef void (*pSPI_CallbackTypeDef)(SPI_HandleTypeDef *hspi); /*!< pointer to an SPI callback function */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPI_Exported_Constants SPI Exported Constants - * @{ - */ - -/** @defgroup SPI_Error_Code SPI Error Code - * @{ - */ -#define HAL_SPI_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_SPI_ERROR_MODF (0x00000001U) /*!< MODF error */ -#define HAL_SPI_ERROR_CRC (0x00000002U) /*!< CRC error */ -#define HAL_SPI_ERROR_OVR (0x00000004U) /*!< OVR error */ -#define HAL_SPI_ERROR_FRE (0x00000008U) /*!< FRE error */ -#define HAL_SPI_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ -#define HAL_SPI_ERROR_FLAG (0x00000020U) /*!< Error on RXNE/TXE/BSY Flag */ -#define HAL_SPI_ERROR_ABORT (0x00000040U) /*!< Error during SPI Abort procedure */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define HAL_SPI_ERROR_INVALID_CALLBACK (0x00000080U) /*!< Invalid Callback error */ -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPI_Mode SPI Mode - * @{ - */ -#define SPI_MODE_SLAVE (0x00000000U) -#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) -/** - * @} - */ - -/** @defgroup SPI_Direction SPI Direction Mode - * @{ - */ -#define SPI_DIRECTION_2LINES (0x00000000U) -#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY -#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE -/** - * @} - */ - -/** @defgroup SPI_Data_Size SPI Data Size - * @{ - */ -#define SPI_DATASIZE_8BIT (0x00000000U) -#define SPI_DATASIZE_16BIT SPI_CR1_DFF -/** - * @} - */ - -/** @defgroup SPI_Clock_Polarity SPI Clock Polarity - * @{ - */ -#define SPI_POLARITY_LOW (0x00000000U) -#define SPI_POLARITY_HIGH SPI_CR1_CPOL -/** - * @} - */ - -/** @defgroup SPI_Clock_Phase SPI Clock Phase - * @{ - */ -#define SPI_PHASE_1EDGE (0x00000000U) -#define SPI_PHASE_2EDGE SPI_CR1_CPHA -/** - * @} - */ - -/** @defgroup SPI_Slave_Select_management SPI Slave Select Management - * @{ - */ -#define SPI_NSS_SOFT SPI_CR1_SSM -#define SPI_NSS_HARD_INPUT (0x00000000U) -#define SPI_NSS_HARD_OUTPUT (SPI_CR2_SSOE << 16U) -/** - * @} - */ - -/** @defgroup SPI_BaudRate_Prescaler SPI BaudRate Prescaler - * @{ - */ -#define SPI_BAUDRATEPRESCALER_2 (0x00000000U) -#define SPI_BAUDRATEPRESCALER_4 (SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_8 (SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_32 (SPI_CR1_BR_2) -#define SPI_BAUDRATEPRESCALER_64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) -/** - * @} - */ - -/** @defgroup SPI_MSB_LSB_transmission SPI MSB LSB Transmission - * @{ - */ -#define SPI_FIRSTBIT_MSB (0x00000000U) -#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST -/** - * @} - */ - -/** @defgroup SPI_TI_mode SPI TI Mode - * @{ - */ -#define SPI_TIMODE_DISABLE (0x00000000U) -#define SPI_TIMODE_ENABLE SPI_CR2_FRF -/** - * @} - */ - -/** @defgroup SPI_CRC_Calculation SPI CRC Calculation - * @{ - */ -#define SPI_CRCCALCULATION_DISABLE (0x00000000U) -#define SPI_CRCCALCULATION_ENABLE SPI_CR1_CRCEN -/** - * @} - */ - -/** @defgroup SPI_Interrupt_definition SPI Interrupt Definition - * @{ - */ -#define SPI_IT_TXE SPI_CR2_TXEIE -#define SPI_IT_RXNE SPI_CR2_RXNEIE -#define SPI_IT_ERR SPI_CR2_ERRIE -/** - * @} - */ - -/** @defgroup SPI_Flags_definition SPI Flags Definition - * @{ - */ -#define SPI_FLAG_RXNE SPI_SR_RXNE /* SPI status flag: Rx buffer not empty flag */ -#define SPI_FLAG_TXE SPI_SR_TXE /* SPI status flag: Tx buffer empty flag */ -#define SPI_FLAG_BSY SPI_SR_BSY /* SPI status flag: Busy flag */ -#define SPI_FLAG_CRCERR SPI_SR_CRCERR /* SPI Error flag: CRC error flag */ -#define SPI_FLAG_MODF SPI_SR_MODF /* SPI Error flag: Mode fault flag */ -#define SPI_FLAG_OVR SPI_SR_OVR /* SPI Error flag: Overrun flag */ -#define SPI_FLAG_FRE SPI_SR_FRE /* SPI Error flag: TI mode frame format error flag */ -#define SPI_FLAG_MASK (SPI_SR_RXNE | SPI_SR_TXE | SPI_SR_BSY | SPI_SR_CRCERR\ - | SPI_SR_MODF | SPI_SR_OVR | SPI_SR_FRE) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup SPI_Exported_Macros SPI Exported Macros - * @{ - */ - -/** @brief Reset SPI handle state. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SPI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET) -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - -/** @brief Enable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Disable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI handle. - * This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Check whether the specified SPI interrupt source is enabled or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the SPI CRCERR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR = (uint16_t)(~SPI_FLAG_CRCERR)) - -/** @brief Clear the SPI MODF pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_modf = 0x00U; \ - tmpreg_modf = (__HANDLE__)->Instance->SR; \ - CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE); \ - UNUSED(tmpreg_modf); \ - } while(0U) - -/** @brief Clear the SPI OVR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = (__HANDLE__)->Instance->DR; \ - tmpreg_ovr = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_ovr); \ - } while(0U) - -/** @brief Clear the SPI FRE pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_fre = 0x00U; \ - tmpreg_fre = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_fre); \ - }while(0U) - -/** @brief Enable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** @brief Disable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPI_Private_Macros SPI Private Macros - * @{ - */ - -/** @brief Set the SPI transmit-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_TX(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Set the SPI receive-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_RX(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Reset the CRC calculation of the SPI. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_RESET_CRC(__HANDLE__) do{CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);\ - SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);}while(0U) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __SR__ copy of SPI SR register. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval SET or RESET. - */ -#define SPI_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__) & ((__FLAG__) & SPI_FLAG_MASK)) == \ - ((__FLAG__) & SPI_FLAG_MASK)) ? SET : RESET) - -/** @brief Check whether the specified SPI Interrupt is set or not. - * @param __CR2__ copy of SPI CR2 register. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval SET or RESET. - */ -#define SPI_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__) & (__INTERRUPT__)) == \ - (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks if SPI Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Mode. - * This parameter can be a value of @ref SPI_Mode - * @retval None - */ -#define IS_SPI_MODE(__MODE__) (((__MODE__) == SPI_MODE_SLAVE) || \ - ((__MODE__) == SPI_MODE_MASTER)) - -/** @brief Checks if SPI Direction Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Direction Mode. - * This parameter can be a value of @ref SPI_Direction - * @retval None - */ -#define IS_SPI_DIRECTION(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_2LINES_RXONLY) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Direction Mode parameter is 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES(__MODE__) ((__MODE__) == SPI_DIRECTION_2LINES) - -/** @brief Checks if SPI Direction Mode parameter is 1 or 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES_OR_1LINE(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Data Size parameter is in allowed range. - * @param __DATASIZE__ specifies the SPI Data Size. - * This parameter can be a value of @ref SPI_Data_Size - * @retval None - */ -#define IS_SPI_DATASIZE(__DATASIZE__) (((__DATASIZE__) == SPI_DATASIZE_16BIT) || \ - ((__DATASIZE__) == SPI_DATASIZE_8BIT)) - -/** @brief Checks if SPI Serial clock steady state parameter is in allowed range. - * @param __CPOL__ specifies the SPI serial clock steady state. - * This parameter can be a value of @ref SPI_Clock_Polarity - * @retval None - */ -#define IS_SPI_CPOL(__CPOL__) (((__CPOL__) == SPI_POLARITY_LOW) || \ - ((__CPOL__) == SPI_POLARITY_HIGH)) - -/** @brief Checks if SPI Clock Phase parameter is in allowed range. - * @param __CPHA__ specifies the SPI Clock Phase. - * This parameter can be a value of @ref SPI_Clock_Phase - * @retval None - */ -#define IS_SPI_CPHA(__CPHA__) (((__CPHA__) == SPI_PHASE_1EDGE) || \ - ((__CPHA__) == SPI_PHASE_2EDGE)) - -/** @brief Checks if SPI Slave Select parameter is in allowed range. - * @param __NSS__ specifies the SPI Slave Select management parameter. - * This parameter can be a value of @ref SPI_Slave_Select_management - * @retval None - */ -#define IS_SPI_NSS(__NSS__) (((__NSS__) == SPI_NSS_SOFT) || \ - ((__NSS__) == SPI_NSS_HARD_INPUT) || \ - ((__NSS__) == SPI_NSS_HARD_OUTPUT)) - -/** @brief Checks if SPI Baudrate prescaler parameter is in allowed range. - * @param __PRESCALER__ specifies the SPI Baudrate prescaler. - * This parameter can be a value of @ref SPI_BaudRate_Prescaler - * @retval None - */ -#define IS_SPI_BAUDRATE_PRESCALER(__PRESCALER__) (((__PRESCALER__) == SPI_BAUDRATEPRESCALER_2) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_4) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_8) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_16) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_32) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_64) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_128) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_256)) - -/** @brief Checks if SPI MSB LSB transmission parameter is in allowed range. - * @param __BIT__ specifies the SPI MSB LSB transmission (whether data transfer starts from MSB or LSB bit). - * This parameter can be a value of @ref SPI_MSB_LSB_transmission - * @retval None - */ -#define IS_SPI_FIRST_BIT(__BIT__) (((__BIT__) == SPI_FIRSTBIT_MSB) || \ - ((__BIT__) == SPI_FIRSTBIT_LSB)) - -/** @brief Checks if SPI TI mode parameter is in allowed range. - * @param __MODE__ specifies the SPI TI mode. - * This parameter can be a value of @ref SPI_TI_mode - * @retval None - */ -#define IS_SPI_TIMODE(__MODE__) (((__MODE__) == SPI_TIMODE_DISABLE) || \ - ((__MODE__) == SPI_TIMODE_ENABLE)) - -/** @brief Checks if SPI CRC calculation enabled state is in allowed range. - * @param __CALCULATION__ specifies the SPI CRC calculation enable state. - * This parameter can be a value of @ref SPI_CRC_Calculation - * @retval None - */ -#define IS_SPI_CRC_CALCULATION(__CALCULATION__) (((__CALCULATION__) == SPI_CRCCALCULATION_DISABLE) || \ - ((__CALCULATION__) == SPI_CRCCALCULATION_ENABLE)) - -/** @brief Checks if SPI polynomial value to be used for the CRC calculation, is in allowed range. - * @param __POLYNOMIAL__ specifies the SPI polynomial value to be used for the CRC calculation. - * This parameter must be a number between Min_Data = 0 and Max_Data = 65535 - * @retval None - */ -#define IS_SPI_CRC_POLYNOMIAL(__POLYNOMIAL__) (((__POLYNOMIAL__) >= 0x1U) && \ - ((__POLYNOMIAL__) <= 0xFFFFU) && \ - (((__POLYNOMIAL__)&0x1U) != 0U)) - -/** @brief Checks if DMA handle is valid. - * @param __HANDLE__ specifies a DMA Handle. - * @retval None - */ -#define IS_SPI_DMA_HANDLE(__HANDLE__) ((__HANDLE__) != NULL) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPI_Exported_Functions - * @{ - */ - -/** @addtogroup SPI_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, - pSPI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi); - -void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi); -uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_SPI_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_spi.h + * @author MCD Application Team + * @brief Header file of SPI HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_SPI_H +#define STM32F4xx_HAL_SPI_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup SPI_Exported_Types SPI Exported Types + * @{ + */ + +/** + * @brief SPI Configuration Structure definition + */ +typedef struct +{ + uint32_t Mode; /*!< Specifies the SPI operating mode. + This parameter can be a value of @ref SPI_Mode */ + + uint32_t Direction; /*!< Specifies the SPI bidirectional mode state. + This parameter can be a value of @ref SPI_Direction */ + + uint32_t DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_Data_Size */ + + uint32_t CLKPolarity; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint32_t NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not. + This parameter can be a value of @ref SPI_TI_mode */ + + uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. + This parameter can be a value of @ref SPI_CRC_Calculation */ + + uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. + This parameter must be an odd number between Min_Data = 1 and Max_Data = 65535 */ +} SPI_InitTypeDef; + +/** + * @brief HAL SPI State structure definition + */ +typedef enum +{ + HAL_SPI_STATE_RESET = 0x00U, /*!< Peripheral not Initialized */ + HAL_SPI_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ + HAL_SPI_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ + HAL_SPI_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ + HAL_SPI_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ + HAL_SPI_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ + HAL_SPI_STATE_ERROR = 0x06U, /*!< SPI error state */ + HAL_SPI_STATE_ABORT = 0x07U /*!< SPI abort is ongoing */ +} HAL_SPI_StateTypeDef; + +/** + * @brief SPI handle Structure definition + */ +typedef struct __SPI_HandleTypeDef +{ + SPI_TypeDef *Instance; /*!< SPI registers base address */ + + SPI_InitTypeDef Init; /*!< SPI communication parameters */ + + uint8_t *pTxBuffPtr; /*!< Pointer to SPI Tx transfer Buffer */ + + uint16_t TxXferSize; /*!< SPI Tx Transfer size */ + + __IO uint16_t TxXferCount; /*!< SPI Tx Transfer Counter */ + + uint8_t *pRxBuffPtr; /*!< Pointer to SPI Rx transfer Buffer */ + + uint16_t RxXferSize; /*!< SPI Rx Transfer size */ + + __IO uint16_t RxXferCount; /*!< SPI Rx Transfer Counter */ + + void (*RxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Rx ISR */ + + void (*TxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Tx ISR */ + + DMA_HandleTypeDef *hdmatx; /*!< SPI Tx DMA Handle parameters */ + + DMA_HandleTypeDef *hdmarx; /*!< SPI Rx DMA Handle parameters */ + + HAL_LockTypeDef Lock; /*!< Locking object */ + + __IO HAL_SPI_StateTypeDef State; /*!< SPI communication state */ + + __IO uint32_t ErrorCode; /*!< SPI Error code */ + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + void (* TxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Completed callback */ + void (* RxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Completed callback */ + void (* TxRxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Completed callback */ + void (* TxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Half Completed callback */ + void (* RxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Half Completed callback */ + void (* TxRxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Half Completed callback */ + void (* ErrorCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Error callback */ + void (* AbortCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Abort callback */ + void (* MspInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp Init callback */ + void (* MspDeInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp DeInit callback */ + +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} SPI_HandleTypeDef; + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +/** + * @brief HAL SPI Callback ID enumeration definition + */ +typedef enum +{ + HAL_SPI_TX_COMPLETE_CB_ID = 0x00U, /*!< SPI Tx Completed callback ID */ + HAL_SPI_RX_COMPLETE_CB_ID = 0x01U, /*!< SPI Rx Completed callback ID */ + HAL_SPI_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< SPI TxRx Completed callback ID */ + HAL_SPI_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< SPI Tx Half Completed callback ID */ + HAL_SPI_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< SPI Rx Half Completed callback ID */ + HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< SPI TxRx Half Completed callback ID */ + HAL_SPI_ERROR_CB_ID = 0x06U, /*!< SPI Error callback ID */ + HAL_SPI_ABORT_CB_ID = 0x07U, /*!< SPI Abort callback ID */ + HAL_SPI_MSPINIT_CB_ID = 0x08U, /*!< SPI Msp Init callback ID */ + HAL_SPI_MSPDEINIT_CB_ID = 0x09U /*!< SPI Msp DeInit callback ID */ + +} HAL_SPI_CallbackIDTypeDef; + +/** + * @brief HAL SPI Callback pointer definition + */ +typedef void (*pSPI_CallbackTypeDef)(SPI_HandleTypeDef *hspi); /*!< pointer to an SPI callback function */ + +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup SPI_Exported_Constants SPI Exported Constants + * @{ + */ + +/** @defgroup SPI_Error_Code SPI Error Code + * @{ + */ +#define HAL_SPI_ERROR_NONE (0x00000000U) /*!< No error */ +#define HAL_SPI_ERROR_MODF (0x00000001U) /*!< MODF error */ +#define HAL_SPI_ERROR_CRC (0x00000002U) /*!< CRC error */ +#define HAL_SPI_ERROR_OVR (0x00000004U) /*!< OVR error */ +#define HAL_SPI_ERROR_FRE (0x00000008U) /*!< FRE error */ +#define HAL_SPI_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ +#define HAL_SPI_ERROR_FLAG (0x00000020U) /*!< Error on RXNE/TXE/BSY Flag */ +#define HAL_SPI_ERROR_ABORT (0x00000040U) /*!< Error during SPI Abort procedure */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +#define HAL_SPI_ERROR_INVALID_CALLBACK (0x00000080U) /*!< Invalid Callback error */ +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup SPI_Mode SPI Mode + * @{ + */ +#define SPI_MODE_SLAVE (0x00000000U) +#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) +/** + * @} + */ + +/** @defgroup SPI_Direction SPI Direction Mode + * @{ + */ +#define SPI_DIRECTION_2LINES (0x00000000U) +#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY +#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE +/** + * @} + */ + +/** @defgroup SPI_Data_Size SPI Data Size + * @{ + */ +#define SPI_DATASIZE_8BIT (0x00000000U) +#define SPI_DATASIZE_16BIT SPI_CR1_DFF +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity SPI Clock Polarity + * @{ + */ +#define SPI_POLARITY_LOW (0x00000000U) +#define SPI_POLARITY_HIGH SPI_CR1_CPOL +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase SPI Clock Phase + * @{ + */ +#define SPI_PHASE_1EDGE (0x00000000U) +#define SPI_PHASE_2EDGE SPI_CR1_CPHA +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management SPI Slave Select Management + * @{ + */ +#define SPI_NSS_SOFT SPI_CR1_SSM +#define SPI_NSS_HARD_INPUT (0x00000000U) +#define SPI_NSS_HARD_OUTPUT (SPI_CR2_SSOE << 16U) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler SPI BaudRate Prescaler + * @{ + */ +#define SPI_BAUDRATEPRESCALER_2 (0x00000000U) +#define SPI_BAUDRATEPRESCALER_4 (SPI_CR1_BR_0) +#define SPI_BAUDRATEPRESCALER_8 (SPI_CR1_BR_1) +#define SPI_BAUDRATEPRESCALER_16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) +#define SPI_BAUDRATEPRESCALER_32 (SPI_CR1_BR_2) +#define SPI_BAUDRATEPRESCALER_64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) +#define SPI_BAUDRATEPRESCALER_128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) +#define SPI_BAUDRATEPRESCALER_256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission SPI MSB LSB Transmission + * @{ + */ +#define SPI_FIRSTBIT_MSB (0x00000000U) +#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST +/** + * @} + */ + +/** @defgroup SPI_TI_mode SPI TI Mode + * @{ + */ +#define SPI_TIMODE_DISABLE (0x00000000U) +#define SPI_TIMODE_ENABLE SPI_CR2_FRF +/** + * @} + */ + +/** @defgroup SPI_CRC_Calculation SPI CRC Calculation + * @{ + */ +#define SPI_CRCCALCULATION_DISABLE (0x00000000U) +#define SPI_CRCCALCULATION_ENABLE SPI_CR1_CRCEN +/** + * @} + */ + +/** @defgroup SPI_Interrupt_definition SPI Interrupt Definition + * @{ + */ +#define SPI_IT_TXE SPI_CR2_TXEIE +#define SPI_IT_RXNE SPI_CR2_RXNEIE +#define SPI_IT_ERR SPI_CR2_ERRIE +/** + * @} + */ + +/** @defgroup SPI_Flags_definition SPI Flags Definition + * @{ + */ +#define SPI_FLAG_RXNE SPI_SR_RXNE /* SPI status flag: Rx buffer not empty flag */ +#define SPI_FLAG_TXE SPI_SR_TXE /* SPI status flag: Tx buffer empty flag */ +#define SPI_FLAG_BSY SPI_SR_BSY /* SPI status flag: Busy flag */ +#define SPI_FLAG_CRCERR SPI_SR_CRCERR /* SPI Error flag: CRC error flag */ +#define SPI_FLAG_MODF SPI_SR_MODF /* SPI Error flag: Mode fault flag */ +#define SPI_FLAG_OVR SPI_SR_OVR /* SPI Error flag: Overrun flag */ +#define SPI_FLAG_FRE SPI_SR_FRE /* SPI Error flag: TI mode frame format error flag */ +#define SPI_FLAG_MASK (SPI_SR_RXNE | SPI_SR_TXE | SPI_SR_BSY | SPI_SR_CRCERR\ + | SPI_SR_MODF | SPI_SR_OVR | SPI_SR_FRE) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macros -----------------------------------------------------------*/ +/** @defgroup SPI_Exported_Macros SPI Exported Macros + * @{ + */ + +/** @brief Reset SPI handle state. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) do{ \ + (__HANDLE__)->State = HAL_SPI_STATE_RESET; \ + (__HANDLE__)->MspInitCallback = NULL; \ + (__HANDLE__)->MspDeInitCallback = NULL; \ + } while(0) +#else +#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET) +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + +/** @brief Enable the specified SPI interrupts. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @param __INTERRUPT__ specifies the interrupt source to enable. + * This parameter can be one of the following values: + * @arg SPI_IT_TXE: Tx buffer empty interrupt enable + * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable + * @arg SPI_IT_ERR: Error interrupt enable + * @retval None + */ +#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) + +/** @brief Disable the specified SPI interrupts. + * @param __HANDLE__ specifies the SPI handle. + * This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral. + * @param __INTERRUPT__ specifies the interrupt source to disable. + * This parameter can be one of the following values: + * @arg SPI_IT_TXE: Tx buffer empty interrupt enable + * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable + * @arg SPI_IT_ERR: Error interrupt enable + * @retval None + */ +#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) + +/** @brief Check whether the specified SPI interrupt source is enabled or not. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @param __INTERRUPT__ specifies the SPI interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_IT_TXE: Tx buffer empty interrupt enable + * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable + * @arg SPI_IT_ERR: Error interrupt enable + * @retval The new state of __IT__ (TRUE or FALSE). + */ +#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ + & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) + +/** @brief Check whether the specified SPI flag is set or not. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg SPI_FLAG_RXNE: Receive buffer not empty flag + * @arg SPI_FLAG_TXE: Transmit buffer empty flag + * @arg SPI_FLAG_CRCERR: CRC error flag + * @arg SPI_FLAG_MODF: Mode fault flag + * @arg SPI_FLAG_OVR: Overrun flag + * @arg SPI_FLAG_BSY: Busy flag + * @arg SPI_FLAG_FRE: Frame format error flag + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) + +/** @brief Clear the SPI CRCERR pending flag. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR = (uint16_t)(~SPI_FLAG_CRCERR)) + +/** @brief Clear the SPI MODF pending flag. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg_modf = 0x00U; \ + tmpreg_modf = (__HANDLE__)->Instance->SR; \ + CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE); \ + UNUSED(tmpreg_modf); \ + } while(0U) + +/** @brief Clear the SPI OVR pending flag. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg_ovr = 0x00U; \ + tmpreg_ovr = (__HANDLE__)->Instance->DR; \ + tmpreg_ovr = (__HANDLE__)->Instance->SR; \ + UNUSED(tmpreg_ovr); \ + } while(0U) + +/** @brief Clear the SPI FRE pending flag. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg_fre = 0x00U; \ + tmpreg_fre = (__HANDLE__)->Instance->SR; \ + UNUSED(tmpreg_fre); \ + }while(0U) + +/** @brief Enable the SPI peripheral. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) + +/** @brief Disable the SPI peripheral. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define __HAL_SPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup SPI_Private_Macros SPI Private Macros + * @{ + */ + +/** @brief Set the SPI transmit-only mode. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define SPI_1LINE_TX(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) + +/** @brief Set the SPI receive-only mode. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define SPI_1LINE_RX(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) + +/** @brief Reset the CRC calculation of the SPI. + * @param __HANDLE__ specifies the SPI Handle. + * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. + * @retval None + */ +#define SPI_RESET_CRC(__HANDLE__) do{CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);\ + SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);}while(0U) + +/** @brief Check whether the specified SPI flag is set or not. + * @param __SR__ copy of SPI SR register. + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg SPI_FLAG_RXNE: Receive buffer not empty flag + * @arg SPI_FLAG_TXE: Transmit buffer empty flag + * @arg SPI_FLAG_CRCERR: CRC error flag + * @arg SPI_FLAG_MODF: Mode fault flag + * @arg SPI_FLAG_OVR: Overrun flag + * @arg SPI_FLAG_BSY: Busy flag + * @arg SPI_FLAG_FRE: Frame format error flag + * @retval SET or RESET. + */ +#define SPI_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__) & ((__FLAG__) & SPI_FLAG_MASK)) == \ + ((__FLAG__) & SPI_FLAG_MASK)) ? SET : RESET) + +/** @brief Check whether the specified SPI Interrupt is set or not. + * @param __CR2__ copy of SPI CR2 register. + * @param __INTERRUPT__ specifies the SPI interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_IT_TXE: Tx buffer empty interrupt enable + * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable + * @arg SPI_IT_ERR: Error interrupt enable + * @retval SET or RESET. + */ +#define SPI_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__) & (__INTERRUPT__)) == \ + (__INTERRUPT__)) ? SET : RESET) + +/** @brief Checks if SPI Mode parameter is in allowed range. + * @param __MODE__ specifies the SPI Mode. + * This parameter can be a value of @ref SPI_Mode + * @retval None + */ +#define IS_SPI_MODE(__MODE__) (((__MODE__) == SPI_MODE_SLAVE) || \ + ((__MODE__) == SPI_MODE_MASTER)) + +/** @brief Checks if SPI Direction Mode parameter is in allowed range. + * @param __MODE__ specifies the SPI Direction Mode. + * This parameter can be a value of @ref SPI_Direction + * @retval None + */ +#define IS_SPI_DIRECTION(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ + ((__MODE__) == SPI_DIRECTION_2LINES_RXONLY) || \ + ((__MODE__) == SPI_DIRECTION_1LINE)) + +/** @brief Checks if SPI Direction Mode parameter is 2 lines. + * @param __MODE__ specifies the SPI Direction Mode. + * @retval None + */ +#define IS_SPI_DIRECTION_2LINES(__MODE__) ((__MODE__) == SPI_DIRECTION_2LINES) + +/** @brief Checks if SPI Direction Mode parameter is 1 or 2 lines. + * @param __MODE__ specifies the SPI Direction Mode. + * @retval None + */ +#define IS_SPI_DIRECTION_2LINES_OR_1LINE(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ + ((__MODE__) == SPI_DIRECTION_1LINE)) + +/** @brief Checks if SPI Data Size parameter is in allowed range. + * @param __DATASIZE__ specifies the SPI Data Size. + * This parameter can be a value of @ref SPI_Data_Size + * @retval None + */ +#define IS_SPI_DATASIZE(__DATASIZE__) (((__DATASIZE__) == SPI_DATASIZE_16BIT) || \ + ((__DATASIZE__) == SPI_DATASIZE_8BIT)) + +/** @brief Checks if SPI Serial clock steady state parameter is in allowed range. + * @param __CPOL__ specifies the SPI serial clock steady state. + * This parameter can be a value of @ref SPI_Clock_Polarity + * @retval None + */ +#define IS_SPI_CPOL(__CPOL__) (((__CPOL__) == SPI_POLARITY_LOW) || \ + ((__CPOL__) == SPI_POLARITY_HIGH)) + +/** @brief Checks if SPI Clock Phase parameter is in allowed range. + * @param __CPHA__ specifies the SPI Clock Phase. + * This parameter can be a value of @ref SPI_Clock_Phase + * @retval None + */ +#define IS_SPI_CPHA(__CPHA__) (((__CPHA__) == SPI_PHASE_1EDGE) || \ + ((__CPHA__) == SPI_PHASE_2EDGE)) + +/** @brief Checks if SPI Slave Select parameter is in allowed range. + * @param __NSS__ specifies the SPI Slave Select management parameter. + * This parameter can be a value of @ref SPI_Slave_Select_management + * @retval None + */ +#define IS_SPI_NSS(__NSS__) (((__NSS__) == SPI_NSS_SOFT) || \ + ((__NSS__) == SPI_NSS_HARD_INPUT) || \ + ((__NSS__) == SPI_NSS_HARD_OUTPUT)) + +/** @brief Checks if SPI Baudrate prescaler parameter is in allowed range. + * @param __PRESCALER__ specifies the SPI Baudrate prescaler. + * This parameter can be a value of @ref SPI_BaudRate_Prescaler + * @retval None + */ +#define IS_SPI_BAUDRATE_PRESCALER(__PRESCALER__) (((__PRESCALER__) == SPI_BAUDRATEPRESCALER_2) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_4) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_8) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_16) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_32) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_64) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_128) || \ + ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_256)) + +/** @brief Checks if SPI MSB LSB transmission parameter is in allowed range. + * @param __BIT__ specifies the SPI MSB LSB transmission (whether data transfer starts from MSB or LSB bit). + * This parameter can be a value of @ref SPI_MSB_LSB_transmission + * @retval None + */ +#define IS_SPI_FIRST_BIT(__BIT__) (((__BIT__) == SPI_FIRSTBIT_MSB) || \ + ((__BIT__) == SPI_FIRSTBIT_LSB)) + +/** @brief Checks if SPI TI mode parameter is in allowed range. + * @param __MODE__ specifies the SPI TI mode. + * This parameter can be a value of @ref SPI_TI_mode + * @retval None + */ +#define IS_SPI_TIMODE(__MODE__) (((__MODE__) == SPI_TIMODE_DISABLE) || \ + ((__MODE__) == SPI_TIMODE_ENABLE)) + +/** @brief Checks if SPI CRC calculation enabled state is in allowed range. + * @param __CALCULATION__ specifies the SPI CRC calculation enable state. + * This parameter can be a value of @ref SPI_CRC_Calculation + * @retval None + */ +#define IS_SPI_CRC_CALCULATION(__CALCULATION__) (((__CALCULATION__) == SPI_CRCCALCULATION_DISABLE) || \ + ((__CALCULATION__) == SPI_CRCCALCULATION_ENABLE)) + +/** @brief Checks if SPI polynomial value to be used for the CRC calculation, is in allowed range. + * @param __POLYNOMIAL__ specifies the SPI polynomial value to be used for the CRC calculation. + * This parameter must be a number between Min_Data = 0 and Max_Data = 65535 + * @retval None + */ +#define IS_SPI_CRC_POLYNOMIAL(__POLYNOMIAL__) (((__POLYNOMIAL__) >= 0x1U) && \ + ((__POLYNOMIAL__) <= 0xFFFFU) && \ + (((__POLYNOMIAL__)&0x1U) != 0U)) + +/** @brief Checks if DMA handle is valid. + * @param __HANDLE__ specifies a DMA Handle. + * @retval None + */ +#define IS_SPI_DMA_HANDLE(__HANDLE__) ((__HANDLE__) != NULL) + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup SPI_Exported_Functions + * @{ + */ + +/** @addtogroup SPI_Exported_Functions_Group1 + * @{ + */ +/* Initialization/de-initialization functions ********************************/ +HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi); +HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi); +void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi); +void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi); + +/* Callbacks Register/UnRegister functions ***********************************/ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, + pSPI_CallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @addtogroup SPI_Exported_Functions_Group2 + * @{ + */ +/* I/O operation functions ***************************************************/ +HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, + uint32_t Timeout); +HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size); +HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size); +HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi); +HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi); +HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi); +/* Transfer Abort functions */ +HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi); +HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi); + +void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi); +void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi); +void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi); +/** + * @} + */ + +/** @addtogroup SPI_Exported_Functions_Group3 + * @{ + */ +/* Peripheral State and Error functions ***************************************/ +HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi); +uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_HAL_SPI_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h index 8c81414..e3cc450 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h @@ -1,2146 +1,2146 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim.h - * @author MCD Application Team - * @brief Header file of TIM HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_H -#define STM32F4xx_HAL_TIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIM_Exported_Types TIM Exported Types - * @{ - */ - -/** - * @brief TIM Time base Configuration Structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_Counter_Mode */ - - uint32_t Period; /*!< Specifies the period value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_ClockDivision */ - - uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - GP timers: this parameter must be a number between Min_Data = 0x00 and - Max_Data = 0xFF. - Advanced timers: this parameter must be a number between Min_Data = 0x0000 and - Max_Data = 0xFFFF. */ - - uint32_t AutoReloadPreload; /*!< Specifies the auto-reload preload. - This parameter can be a value of @ref TIM_AutoReloadPreload */ -} TIM_Base_InitTypeDef; - -/** - * @brief TIM Output Compare Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCFastMode; /*!< Specifies the Fast mode state. - This parameter can be a value of @ref TIM_Output_Fast_State - @note This parameter is valid only in PWM1 and PWM2 mode. */ - - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ -} TIM_OC_InitTypeDef; - -/** - * @brief TIM One Pulse Mode Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_OnePulse_InitTypeDef; - -/** - * @brief TIM Input Capture Configuration Structure definition - */ -typedef struct -{ - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_IC_InitTypeDef; - -/** - * @brief TIM Encoder Configuration Structure definition - */ -typedef struct -{ - uint32_t EncoderMode; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Mode */ - - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC1Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t IC2Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC2Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC2Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC2Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_Encoder_InitTypeDef; - -/** - * @brief Clock Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClockSource; /*!< TIM clock sources - This parameter can be a value of @ref TIM_Clock_Source */ - uint32_t ClockPolarity; /*!< TIM clock polarity - This parameter can be a value of @ref TIM_Clock_Polarity */ - uint32_t ClockPrescaler; /*!< TIM clock prescaler - This parameter can be a value of @ref TIM_Clock_Prescaler */ - uint32_t ClockFilter; /*!< TIM clock filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClockConfigTypeDef; - -/** - * @brief TIM Clear Input Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClearInputState; /*!< TIM clear Input state - This parameter can be ENABLE or DISABLE */ - uint32_t ClearInputSource; /*!< TIM clear Input sources - This parameter can be a value of @ref TIM_ClearInput_Source */ - uint32_t ClearInputPolarity; /*!< TIM Clear Input polarity - This parameter can be a value of @ref TIM_ClearInput_Polarity */ - uint32_t ClearInputPrescaler; /*!< TIM Clear Input prescaler - This parameter must be 0: When OCRef clear feature is used with ETR source, - ETR prescaler must be off */ - uint32_t ClearInputFilter; /*!< TIM Clear Input filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClearInputConfigTypeDef; - -/** - * @brief TIM Master configuration Structure definition - */ -typedef struct -{ - uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection - This parameter can be a value of @ref TIM_Master_Mode_Selection */ - uint32_t MasterSlaveMode; /*!< Master/slave mode selection - This parameter can be a value of @ref TIM_Master_Slave_Mode - @note When the Master/slave mode is enabled, the effect of - an event on the trigger input (TRGI) is delayed to allow a - perfect synchronization between the current timer and its - slaves (through TRGO). It is not mandatory in case of timer - synchronization mode. */ -} TIM_MasterConfigTypeDef; - -/** - * @brief TIM Slave configuration Structure definition - */ -typedef struct -{ - uint32_t SlaveMode; /*!< Slave mode selection - This parameter can be a value of @ref TIM_Slave_Mode */ - uint32_t InputTrigger; /*!< Input Trigger source - This parameter can be a value of @ref TIM_Trigger_Selection */ - uint32_t TriggerPolarity; /*!< Input Trigger polarity - This parameter can be a value of @ref TIM_Trigger_Polarity */ - uint32_t TriggerPrescaler; /*!< Input trigger prescaler - This parameter can be a value of @ref TIM_Trigger_Prescaler */ - uint32_t TriggerFilter; /*!< Input trigger filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - -} TIM_SlaveConfigTypeDef; - -/** - * @brief TIM Break input(s) and Dead time configuration Structure definition - * @note 2 break inputs can be configured (BKIN and BKIN2) with configurable - * filter and polarity. - */ -typedef struct -{ - uint32_t OffStateRunMode; /*!< TIM off state in run mode, This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ - - uint32_t OffStateIDLEMode; /*!< TIM off state in IDLE mode, This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ - - uint32_t LockLevel; /*!< TIM Lock level, This parameter can be a value of @ref TIM_Lock_level */ - - uint32_t DeadTime; /*!< TIM dead Time, This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - - uint32_t BreakState; /*!< TIM Break State, This parameter can be a value of @ref TIM_Break_Input_enable_disable */ - - uint32_t BreakPolarity; /*!< TIM Break input polarity, This parameter can be a value of @ref TIM_Break_Polarity */ - - uint32_t BreakFilter; /*!< Specifies the break input filter.This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t AutomaticOutput; /*!< TIM Automatic Output Enable state, This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ - -} TIM_BreakDeadTimeConfigTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_TIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ - HAL_TIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_TIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_TIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_TIM_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ -} HAL_TIM_StateTypeDef; - -/** - * @brief TIM Channel States definition - */ -typedef enum -{ - HAL_TIM_CHANNEL_STATE_RESET = 0x00U, /*!< TIM Channel initial state */ - HAL_TIM_CHANNEL_STATE_READY = 0x01U, /*!< TIM Channel ready for use */ - HAL_TIM_CHANNEL_STATE_BUSY = 0x02U, /*!< An internal process is ongoing on the TIM channel */ -} HAL_TIM_ChannelStateTypeDef; - -/** - * @brief DMA Burst States definition - */ -typedef enum -{ - HAL_DMA_BURST_STATE_RESET = 0x00U, /*!< DMA Burst initial state */ - HAL_DMA_BURST_STATE_READY = 0x01U, /*!< DMA Burst ready for use */ - HAL_DMA_BURST_STATE_BUSY = 0x02U, /*!< Ongoing DMA Burst */ -} HAL_TIM_DMABurstStateTypeDef; - -/** - * @brief HAL Active channel structures definition - */ -typedef enum -{ - HAL_TIM_ACTIVE_CHANNEL_1 = 0x01U, /*!< The active channel is 1 */ - HAL_TIM_ACTIVE_CHANNEL_2 = 0x02U, /*!< The active channel is 2 */ - HAL_TIM_ACTIVE_CHANNEL_3 = 0x04U, /*!< The active channel is 3 */ - HAL_TIM_ACTIVE_CHANNEL_4 = 0x08U, /*!< The active channel is 4 */ - HAL_TIM_ACTIVE_CHANNEL_CLEARED = 0x00U /*!< All active channels cleared */ -} HAL_TIM_ActiveChannel; - -/** - * @brief TIM Time Base Handle Structure definition - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -typedef struct __TIM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -{ - TIM_TypeDef *Instance; /*!< Register base address */ - TIM_Base_InitTypeDef Init; /*!< TIM Time Base required parameters */ - HAL_TIM_ActiveChannel Channel; /*!< Active channel */ - DMA_HandleTypeDef *hdma[7]; /*!< DMA Handlers array - This array is accessed by a @ref DMA_Handle_index */ - HAL_LockTypeDef Lock; /*!< Locking object */ - __IO HAL_TIM_StateTypeDef State; /*!< TIM operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelState[4]; /*!< TIM channel operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelNState[4]; /*!< TIM complementary channel operation state */ - __IO HAL_TIM_DMABurstStateTypeDef DMABurstState; /*!< DMA burst operation state */ - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - void (* Base_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp Init Callback */ - void (* Base_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp DeInit Callback */ - void (* IC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp Init Callback */ - void (* IC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp DeInit Callback */ - void (* OC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp Init Callback */ - void (* OC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp DeInit Callback */ - void (* PWM_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp Init Callback */ - void (* PWM_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp DeInit Callback */ - void (* OnePulse_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp Init Callback */ - void (* OnePulse_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp DeInit Callback */ - void (* Encoder_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp Init Callback */ - void (* Encoder_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp DeInit Callback */ - void (* HallSensor_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp Init Callback */ - void (* HallSensor_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp DeInit Callback */ - void (* PeriodElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed Callback */ - void (* PeriodElapsedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed half complete Callback */ - void (* TriggerCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger Callback */ - void (* TriggerHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger half complete Callback */ - void (* IC_CaptureCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture Callback */ - void (* IC_CaptureHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture half complete Callback */ - void (* OC_DelayElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Output Compare Delay Elapsed Callback */ - void (* PWM_PulseFinishedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished Callback */ - void (* PWM_PulseFinishedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished half complete Callback */ - void (* ErrorCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Error Callback */ - void (* CommutationCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation Callback */ - void (* CommutationHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation half complete Callback */ - void (* BreakCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Break Callback */ -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} TIM_HandleTypeDef; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL TIM Callback ID enumeration definition - */ -typedef enum -{ - HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */ - , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */ - , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */ - , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */ - , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */ - , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */ - , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */ - , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */ - , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */ - , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */ - , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */ - , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */ - - , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */ - , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */ - , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */ - , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */ - , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */ - , HAL_TIM_COMMUTATION_HALF_CB_ID = 0x19U /*!< TIM Commutation half complete Callback ID */ - , HAL_TIM_BREAK_CB_ID = 0x1AU /*!< TIM Break Callback ID */ -} HAL_TIM_CallbackIDTypeDef; - -/** - * @brief HAL TIM Callback pointer definition - */ -typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to the TIM callback function */ - -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIM_Exported_Constants TIM Exported Constants - * @{ - */ - -/** @defgroup TIM_ClearInput_Source TIM Clear Input Source - * @{ - */ -#define TIM_CLEARINPUTSOURCE_NONE 0x00000000U /*!< OCREF_CLR is disabled */ -#define TIM_CLEARINPUTSOURCE_ETR 0x00000001U /*!< OCREF_CLR is connected to ETRF input */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Base_address TIM DMA Base Address - * @{ - */ -#define TIM_DMABASE_CR1 0x00000000U -#define TIM_DMABASE_CR2 0x00000001U -#define TIM_DMABASE_SMCR 0x00000002U -#define TIM_DMABASE_DIER 0x00000003U -#define TIM_DMABASE_SR 0x00000004U -#define TIM_DMABASE_EGR 0x00000005U -#define TIM_DMABASE_CCMR1 0x00000006U -#define TIM_DMABASE_CCMR2 0x00000007U -#define TIM_DMABASE_CCER 0x00000008U -#define TIM_DMABASE_CNT 0x00000009U -#define TIM_DMABASE_PSC 0x0000000AU -#define TIM_DMABASE_ARR 0x0000000BU -#define TIM_DMABASE_RCR 0x0000000CU -#define TIM_DMABASE_CCR1 0x0000000DU -#define TIM_DMABASE_CCR2 0x0000000EU -#define TIM_DMABASE_CCR3 0x0000000FU -#define TIM_DMABASE_CCR4 0x00000010U -#define TIM_DMABASE_BDTR 0x00000011U -#define TIM_DMABASE_DCR 0x00000012U -#define TIM_DMABASE_DMAR 0x00000013U -/** - * @} - */ - -/** @defgroup TIM_Event_Source TIM Event Source - * @{ - */ -#define TIM_EVENTSOURCE_UPDATE TIM_EGR_UG /*!< Reinitialize the counter and generates an update of the registers */ -#define TIM_EVENTSOURCE_CC1 TIM_EGR_CC1G /*!< A capture/compare event is generated on channel 1 */ -#define TIM_EVENTSOURCE_CC2 TIM_EGR_CC2G /*!< A capture/compare event is generated on channel 2 */ -#define TIM_EVENTSOURCE_CC3 TIM_EGR_CC3G /*!< A capture/compare event is generated on channel 3 */ -#define TIM_EVENTSOURCE_CC4 TIM_EGR_CC4G /*!< A capture/compare event is generated on channel 4 */ -#define TIM_EVENTSOURCE_COM TIM_EGR_COMG /*!< A commutation event is generated */ -#define TIM_EVENTSOURCE_TRIGGER TIM_EGR_TG /*!< A trigger event is generated */ -#define TIM_EVENTSOURCE_BREAK TIM_EGR_BG /*!< A break event is generated */ -/** - * @} - */ - -/** @defgroup TIM_Input_Channel_Polarity TIM Input Channel polarity - * @{ - */ -#define TIM_INPUTCHANNELPOLARITY_RISING 0x00000000U /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_FALLING TIM_CCER_CC1P /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< Polarity for TIx source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Polarity TIM ETR Polarity - * @{ - */ -#define TIM_ETRPOLARITY_INVERTED TIM_SMCR_ETP /*!< Polarity for ETR source */ -#define TIM_ETRPOLARITY_NONINVERTED 0x00000000U /*!< Polarity for ETR source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Prescaler TIM ETR Prescaler - * @{ - */ -#define TIM_ETRPRESCALER_DIV1 0x00000000U /*!< No prescaler is used */ -#define TIM_ETRPRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR input source is divided by 2 */ -#define TIM_ETRPRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR input source is divided by 4 */ -#define TIM_ETRPRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR input source is divided by 8 */ -/** - * @} - */ - -/** @defgroup TIM_Counter_Mode TIM Counter Mode - * @{ - */ -#define TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as up-counter */ -#define TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as down-counter */ -#define TIM_COUNTERMODE_CENTERALIGNED1 TIM_CR1_CMS_0 /*!< Center-aligned mode 1 */ -#define TIM_COUNTERMODE_CENTERALIGNED2 TIM_CR1_CMS_1 /*!< Center-aligned mode 2 */ -#define TIM_COUNTERMODE_CENTERALIGNED3 TIM_CR1_CMS /*!< Center-aligned mode 3 */ -/** - * @} - */ - -/** @defgroup TIM_ClockDivision TIM Clock Division - * @{ - */ -#define TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< Clock division: tDTS=tCK_INT */ -#define TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< Clock division: tDTS=2*tCK_INT */ -#define TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< Clock division: tDTS=4*tCK_INT */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_State TIM Output Compare State - * @{ - */ -#define TIM_OUTPUTSTATE_DISABLE 0x00000000U /*!< Capture/Compare 1 output disabled */ -#define TIM_OUTPUTSTATE_ENABLE TIM_CCER_CC1E /*!< Capture/Compare 1 output enabled */ -/** - * @} - */ - -/** @defgroup TIM_AutoReloadPreload TIM Auto-Reload Preload - * @{ - */ -#define TIM_AUTORELOAD_PRELOAD_DISABLE 0x00000000U /*!< TIMx_ARR register is not buffered */ -#define TIM_AUTORELOAD_PRELOAD_ENABLE TIM_CR1_ARPE /*!< TIMx_ARR register is buffered */ - -/** - * @} - */ - -/** @defgroup TIM_Output_Fast_State TIM Output Fast State - * @{ - */ -#define TIM_OCFAST_DISABLE 0x00000000U /*!< Output Compare fast disable */ -#define TIM_OCFAST_ENABLE TIM_CCMR1_OC1FE /*!< Output Compare fast enable */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_State TIM Complementary Output Compare State - * @{ - */ -#define TIM_OUTPUTNSTATE_DISABLE 0x00000000U /*!< OCxN is disabled */ -#define TIM_OUTPUTNSTATE_ENABLE TIM_CCER_CC1NE /*!< OCxN is enabled */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Polarity TIM Output Compare Polarity - * @{ - */ -#define TIM_OCPOLARITY_HIGH 0x00000000U /*!< Capture/Compare output polarity */ -#define TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< Capture/Compare output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Polarity TIM Complementary Output Compare Polarity - * @{ - */ -#define TIM_OCNPOLARITY_HIGH 0x00000000U /*!< Capture/Compare complementary output polarity */ -#define TIM_OCNPOLARITY_LOW TIM_CCER_CC1NP /*!< Capture/Compare complementary output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Idle_State TIM Output Compare Idle State - * @{ - */ -#define TIM_OCIDLESTATE_SET TIM_CR2_OIS1 /*!< Output Idle state: OCx=1 when MOE=0 */ -#define TIM_OCIDLESTATE_RESET 0x00000000U /*!< Output Idle state: OCx=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Idle_State TIM Complementary Output Compare Idle State - * @{ - */ -#define TIM_OCNIDLESTATE_SET TIM_CR2_OIS1N /*!< Complementary output Idle state: OCxN=1 when MOE=0 */ -#define TIM_OCNIDLESTATE_RESET 0x00000000U /*!< Complementary output Idle state: OCxN=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Polarity TIM Input Capture Polarity - * @{ - */ -#define TIM_ICPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Capture triggered by rising edge on timer input */ -#define TIM_ICPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Capture triggered by falling edge on timer input */ -#define TIM_ICPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Capture triggered by both rising and falling edges on timer input*/ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Input_Polarity TIM Encoder Input Polarity - * @{ - */ -#define TIM_ENCODERINPUTPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Encoder input with rising edge polarity */ -#define TIM_ENCODERINPUTPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Encoder input with falling edge polarity */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Selection TIM Input Capture Selection - * @{ - */ -#define TIM_ICSELECTION_DIRECTTI TIM_CCMR1_CC1S_0 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC1, IC2, IC3 or IC4, respectively */ -#define TIM_ICSELECTION_INDIRECTTI TIM_CCMR1_CC1S_1 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC2, IC1, IC4 or IC3, respectively */ -#define TIM_ICSELECTION_TRC TIM_CCMR1_CC1S /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Prescaler TIM Input Capture Prescaler - * @{ - */ -#define TIM_ICPSC_DIV1 0x00000000U /*!< Capture performed each time an edge is detected on the capture input */ -#define TIM_ICPSC_DIV2 TIM_CCMR1_IC1PSC_0 /*!< Capture performed once every 2 events */ -#define TIM_ICPSC_DIV4 TIM_CCMR1_IC1PSC_1 /*!< Capture performed once every 4 events */ -#define TIM_ICPSC_DIV8 TIM_CCMR1_IC1PSC /*!< Capture performed once every 8 events */ -/** - * @} - */ - -/** @defgroup TIM_One_Pulse_Mode TIM One Pulse Mode - * @{ - */ -#define TIM_OPMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ -#define TIM_OPMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Mode TIM Encoder Mode - * @{ - */ -#define TIM_ENCODERMODE_TI1 TIM_SMCR_SMS_0 /*!< Quadrature encoder mode 1, x2 mode, counts up/down on TI1FP1 edge depending on TI2FP2 level */ -#define TIM_ENCODERMODE_TI2 TIM_SMCR_SMS_1 /*!< Quadrature encoder mode 2, x2 mode, counts up/down on TI2FP2 edge depending on TI1FP1 level. */ -#define TIM_ENCODERMODE_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Quadrature encoder mode 3, x4 mode, counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input. */ -/** - * @} - */ - -/** @defgroup TIM_Interrupt_definition TIM interrupt Definition - * @{ - */ -#define TIM_IT_UPDATE TIM_DIER_UIE /*!< Update interrupt */ -#define TIM_IT_CC1 TIM_DIER_CC1IE /*!< Capture/Compare 1 interrupt */ -#define TIM_IT_CC2 TIM_DIER_CC2IE /*!< Capture/Compare 2 interrupt */ -#define TIM_IT_CC3 TIM_DIER_CC3IE /*!< Capture/Compare 3 interrupt */ -#define TIM_IT_CC4 TIM_DIER_CC4IE /*!< Capture/Compare 4 interrupt */ -#define TIM_IT_COM TIM_DIER_COMIE /*!< Commutation interrupt */ -#define TIM_IT_TRIGGER TIM_DIER_TIE /*!< Trigger interrupt */ -#define TIM_IT_BREAK TIM_DIER_BIE /*!< Break interrupt */ -/** - * @} - */ - -/** @defgroup TIM_Commutation_Source TIM Commutation Source - * @{ - */ -#define TIM_COMMUTATION_TRGI TIM_CR2_CCUS /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit or when an rising edge occurs on trigger input */ -#define TIM_COMMUTATION_SOFTWARE 0x00000000U /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit */ -/** - * @} - */ - -/** @defgroup TIM_DMA_sources TIM DMA Sources - * @{ - */ -#define TIM_DMA_UPDATE TIM_DIER_UDE /*!< DMA request is triggered by the update event */ -#define TIM_DMA_CC1 TIM_DIER_CC1DE /*!< DMA request is triggered by the capture/compare macth 1 event */ -#define TIM_DMA_CC2 TIM_DIER_CC2DE /*!< DMA request is triggered by the capture/compare macth 2 event event */ -#define TIM_DMA_CC3 TIM_DIER_CC3DE /*!< DMA request is triggered by the capture/compare macth 3 event event */ -#define TIM_DMA_CC4 TIM_DIER_CC4DE /*!< DMA request is triggered by the capture/compare macth 4 event event */ -#define TIM_DMA_COM TIM_DIER_COMDE /*!< DMA request is triggered by the commutation event */ -#define TIM_DMA_TRIGGER TIM_DIER_TDE /*!< DMA request is triggered by the trigger event */ -/** - * @} - */ - -/** @defgroup TIM_CC_DMA_Request CCx DMA request selection - * @{ - */ -#define TIM_CCDMAREQUEST_CC 0x00000000U /*!< CCx DMA request sent when capture or compare match event occurs */ -#define TIM_CCDMAREQUEST_UPDATE TIM_CR2_CCDS /*!< CCx DMA requests sent when update event occurs */ -/** - * @} - */ - -/** @defgroup TIM_Flag_definition TIM Flag Definition - * @{ - */ -#define TIM_FLAG_UPDATE TIM_SR_UIF /*!< Update interrupt flag */ -#define TIM_FLAG_CC1 TIM_SR_CC1IF /*!< Capture/Compare 1 interrupt flag */ -#define TIM_FLAG_CC2 TIM_SR_CC2IF /*!< Capture/Compare 2 interrupt flag */ -#define TIM_FLAG_CC3 TIM_SR_CC3IF /*!< Capture/Compare 3 interrupt flag */ -#define TIM_FLAG_CC4 TIM_SR_CC4IF /*!< Capture/Compare 4 interrupt flag */ -#define TIM_FLAG_COM TIM_SR_COMIF /*!< Commutation interrupt flag */ -#define TIM_FLAG_TRIGGER TIM_SR_TIF /*!< Trigger interrupt flag */ -#define TIM_FLAG_BREAK TIM_SR_BIF /*!< Break interrupt flag */ -#define TIM_FLAG_CC1OF TIM_SR_CC1OF /*!< Capture 1 overcapture flag */ -#define TIM_FLAG_CC2OF TIM_SR_CC2OF /*!< Capture 2 overcapture flag */ -#define TIM_FLAG_CC3OF TIM_SR_CC3OF /*!< Capture 3 overcapture flag */ -#define TIM_FLAG_CC4OF TIM_SR_CC4OF /*!< Capture 4 overcapture flag */ -/** - * @} - */ - -/** @defgroup TIM_Channel TIM Channel - * @{ - */ -#define TIM_CHANNEL_1 0x00000000U /*!< Capture/compare channel 1 identifier */ -#define TIM_CHANNEL_2 0x00000004U /*!< Capture/compare channel 2 identifier */ -#define TIM_CHANNEL_3 0x00000008U /*!< Capture/compare channel 3 identifier */ -#define TIM_CHANNEL_4 0x0000000CU /*!< Capture/compare channel 4 identifier */ -#define TIM_CHANNEL_ALL 0x0000003CU /*!< Global Capture/compare channel identifier */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Source TIM Clock Source - * @{ - */ -#define TIM_CLOCKSOURCE_INTERNAL TIM_SMCR_ETPS_0 /*!< Internal clock source */ -#define TIM_CLOCKSOURCE_ETRMODE1 TIM_TS_ETRF /*!< External clock source mode 1 (ETRF) */ -#define TIM_CLOCKSOURCE_ETRMODE2 TIM_SMCR_ETPS_1 /*!< External clock source mode 2 */ -#define TIM_CLOCKSOURCE_TI1ED TIM_TS_TI1F_ED /*!< External clock source mode 1 (TTI1FP1 + edge detect.) */ -#define TIM_CLOCKSOURCE_TI1 TIM_TS_TI1FP1 /*!< External clock source mode 1 (TTI1FP1) */ -#define TIM_CLOCKSOURCE_TI2 TIM_TS_TI2FP2 /*!< External clock source mode 1 (TTI2FP2) */ -#define TIM_CLOCKSOURCE_ITR0 TIM_TS_ITR0 /*!< External clock source mode 1 (ITR0) */ -#define TIM_CLOCKSOURCE_ITR1 TIM_TS_ITR1 /*!< External clock source mode 1 (ITR1) */ -#define TIM_CLOCKSOURCE_ITR2 TIM_TS_ITR2 /*!< External clock source mode 1 (ITR2) */ -#define TIM_CLOCKSOURCE_ITR3 TIM_TS_ITR3 /*!< External clock source mode 1 (ITR3) */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Polarity TIM Clock Polarity - * @{ - */ -#define TIM_CLOCKPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIx clock sources */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Prescaler TIM Clock Prescaler - * @{ - */ -#define TIM_CLOCKPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLOCKPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Clock: Capture performed once every 2 events. */ -#define TIM_CLOCKPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Clock: Capture performed once every 4 events. */ -#define TIM_CLOCKPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Clock: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Polarity TIM Clear Input Polarity - * @{ - */ -#define TIM_CLEARINPUTPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx pin */ -#define TIM_CLEARINPUTPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx pin */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Prescaler TIM Clear Input Prescaler - * @{ - */ -#define TIM_CLEARINPUTPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLEARINPUTPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR pin: Capture performed once every 2 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR pin: Capture performed once every 4 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR pin: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state TIM OSSR OffState Selection for Run mode state - * @{ - */ -#define TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ - -/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state TIM OSSI OffState Selection for Idle mode state - * @{ - */ -#define TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ -/** @defgroup TIM_Lock_level TIM Lock level - * @{ - */ -#define TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF */ -#define TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */ -#define TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */ -#define TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */ -/** - * @} - */ - -/** @defgroup TIM_Break_Input_enable_disable TIM Break Input Enable - * @{ - */ -#define TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break input BRK is enabled */ -#define TIM_BREAK_DISABLE 0x00000000U /*!< Break input BRK is disabled */ -/** - * @} - */ - -/** @defgroup TIM_Break_Polarity TIM Break Input Polarity - * @{ - */ -#define TIM_BREAKPOLARITY_LOW 0x00000000U /*!< Break input BRK is active low */ -#define TIM_BREAKPOLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */ -/** - * @} - */ - -/** @defgroup TIM_AOE_Bit_Set_Reset TIM Automatic Output Enable - * @{ - */ -#define TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ -#define TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event (if none of the break inputs BRK and BRK2 is active) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Mode_Selection TIM Master Mode Selection - * @{ - */ -#define TIM_TRGO_RESET 0x00000000U /*!< TIMx_EGR.UG bit is used as trigger output (TRGO) */ -#define TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< TIMx_CR1.CEN bit is used as trigger output (TRGO) */ -#define TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1 (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< Capture or a compare match 1 is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output (TRGO) */ -#define TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output(TRGO) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Slave_Mode TIM Master/Slave Mode - * @{ - */ -#define TIM_MASTERSLAVEMODE_ENABLE TIM_SMCR_MSM /*!< No action */ -#define TIM_MASTERSLAVEMODE_DISABLE 0x00000000U /*!< Master/slave mode is selected */ -/** - * @} - */ - -/** @defgroup TIM_Slave_Mode TIM Slave mode - * @{ - */ -#define TIM_SLAVEMODE_DISABLE 0x00000000U /*!< Slave mode disabled */ -#define TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode */ -#define TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode */ -#define TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode */ -#define TIM_SLAVEMODE_EXTERNAL1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< External Clock Mode 1 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_and_PWM_modes TIM Output Compare and PWM Modes - * @{ - */ -#define TIM_OCMODE_TIMING 0x00000000U /*!< Frozen */ -#define TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!< Set channel to active level on match */ -#define TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!< Set channel to inactive level on match */ -#define TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< Toggle */ -#define TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!< PWM mode 1 */ -#define TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< PWM mode 2 */ -#define TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!< Force active level */ -#define TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!< Force inactive level */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Selection TIM Trigger Selection - * @{ - */ -#define TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) */ -#define TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) */ -#define TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) */ -#define TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) */ -#define TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) */ -#define TIM_TS_TI1FP1 (TIM_SMCR_TS_0 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 1 (TI1FP1) */ -#define TIM_TS_TI2FP2 (TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 2 (TI2FP2) */ -#define TIM_TS_ETRF (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered External Trigger input (ETRF) */ -#define TIM_TS_NONE 0x0000FFFFU /*!< No trigger selected */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Polarity TIM Trigger Polarity - * @{ - */ -#define TIM_TRIGGERPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Prescaler TIM Trigger Prescaler - * @{ - */ -#define TIM_TRIGGERPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_TRIGGERPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Trigger: Capture performed once every 2 events. */ -#define TIM_TRIGGERPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Trigger: Capture performed once every 4 events. */ -#define TIM_TRIGGERPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Trigger: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_TI1_Selection TIM TI1 Input Selection - * @{ - */ -#define TIM_TI1SELECTION_CH1 0x00000000U /*!< The TIMx_CH1 pin is connected to TI1 input */ -#define TIM_TI1SELECTION_XORCOMBINATION TIM_CR2_TI1S /*!< The TIMx_CH1, CH2 and CH3 pins are connected to the TI1 input (XOR combination) */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Burst_Length TIM DMA Burst Length - * @{ - */ -#define TIM_DMABURSTLENGTH_1TRANSFER 0x00000000U /*!< The transfer is done to 1 register starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_2TRANSFERS 0x00000100U /*!< The transfer is done to 2 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_3TRANSFERS 0x00000200U /*!< The transfer is done to 3 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_4TRANSFERS 0x00000300U /*!< The transfer is done to 4 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_5TRANSFERS 0x00000400U /*!< The transfer is done to 5 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_6TRANSFERS 0x00000500U /*!< The transfer is done to 6 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_7TRANSFERS 0x00000600U /*!< The transfer is done to 7 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_8TRANSFERS 0x00000700U /*!< The transfer is done to 8 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_9TRANSFERS 0x00000800U /*!< The transfer is done to 9 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_10TRANSFERS 0x00000900U /*!< The transfer is done to 10 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_11TRANSFERS 0x00000A00U /*!< The transfer is done to 11 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_12TRANSFERS 0x00000B00U /*!< The transfer is done to 12 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_13TRANSFERS 0x00000C00U /*!< The transfer is done to 13 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_14TRANSFERS 0x00000D00U /*!< The transfer is done to 14 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_15TRANSFERS 0x00000E00U /*!< The transfer is done to 15 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_16TRANSFERS 0x00000F00U /*!< The transfer is done to 16 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_17TRANSFERS 0x00001000U /*!< The transfer is done to 17 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_18TRANSFERS 0x00001100U /*!< The transfer is done to 18 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -/** - * @} - */ - -/** @defgroup DMA_Handle_index TIM DMA Handle Index - * @{ - */ -#define TIM_DMA_ID_UPDATE ((uint16_t) 0x0000) /*!< Index of the DMA handle used for Update DMA requests */ -#define TIM_DMA_ID_CC1 ((uint16_t) 0x0001) /*!< Index of the DMA handle used for Capture/Compare 1 DMA requests */ -#define TIM_DMA_ID_CC2 ((uint16_t) 0x0002) /*!< Index of the DMA handle used for Capture/Compare 2 DMA requests */ -#define TIM_DMA_ID_CC3 ((uint16_t) 0x0003) /*!< Index of the DMA handle used for Capture/Compare 3 DMA requests */ -#define TIM_DMA_ID_CC4 ((uint16_t) 0x0004) /*!< Index of the DMA handle used for Capture/Compare 4 DMA requests */ -#define TIM_DMA_ID_COMMUTATION ((uint16_t) 0x0005) /*!< Index of the DMA handle used for Commutation DMA requests */ -#define TIM_DMA_ID_TRIGGER ((uint16_t) 0x0006) /*!< Index of the DMA handle used for Trigger DMA requests */ -/** - * @} - */ - -/** @defgroup Channel_CC_State TIM Capture/Compare Channel State - * @{ - */ -#define TIM_CCx_ENABLE 0x00000001U /*!< Input or output channel is enabled */ -#define TIM_CCx_DISABLE 0x00000000U /*!< Input or output channel is disabled */ -#define TIM_CCxN_ENABLE 0x00000004U /*!< Complementary output channel is enabled */ -#define TIM_CCxN_DISABLE 0x00000000U /*!< Complementary output channel is enabled */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup TIM_Exported_Macros TIM Exported Macros - * @{ - */ - -/** @brief Reset TIM handle state. - * @param __HANDLE__ TIM handle. - * @retval None - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - (__HANDLE__)->Base_MspInitCallback = NULL; \ - (__HANDLE__)->Base_MspDeInitCallback = NULL; \ - (__HANDLE__)->IC_MspInitCallback = NULL; \ - (__HANDLE__)->IC_MspDeInitCallback = NULL; \ - (__HANDLE__)->OC_MspInitCallback = NULL; \ - (__HANDLE__)->OC_MspDeInitCallback = NULL; \ - (__HANDLE__)->PWM_MspInitCallback = NULL; \ - (__HANDLE__)->PWM_MspDeInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspDeInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspDeInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - } while(0) -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @brief Enable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|=(TIM_CR1_CEN)) - -/** - * @brief Enable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_MOE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->BDTR|=(TIM_BDTR_MOE)) - -/** - * @brief Disable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->CR1 &= ~(TIM_CR1_CEN); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled only if all the CCx and CCxN channels have been - * disabled - */ -#define __HAL_TIM_MOE_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled unconditionally - */ -#define __HAL_TIM_MOE_DISABLE_UNCONDITIONALLY(__HANDLE__) (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE) - -/** @brief Enable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to enable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER |= (__INTERRUPT__)) - -/** @brief Disable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to disable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER &= ~(__INTERRUPT__)) - -/** @brief Enable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to enable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_ENABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER |= (__DMA__)) - -/** @brief Disable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to disable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_DISABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER &= ~(__DMA__)) - -/** @brief Check whether the specified TIM interrupt flag is set or not. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to check. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR &(__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified TIM interrupt flag. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to clear. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** - * @brief Check whether the specified TIM interrupt source is enabled or not. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the TIM interrupt source to check. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval The state of TIM_IT (SET or RESET). - */ -#define __HAL_TIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->DIER & (__INTERRUPT__)) \ - == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Clear the TIM interrupt pending bits. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->SR = ~(__INTERRUPT__)) - -/** - * @brief Indicates whether or not the TIM Counter is used as downcounter. - * @param __HANDLE__ TIM handle. - * @retval False (Counter used as upcounter) or True (Counter used as downcounter) - * @note This macro is particularly useful to get the counting mode when the timer operates in Center-aligned mode - * or Encoder mode. - */ -#define __HAL_TIM_IS_TIM_COUNTING_DOWN(__HANDLE__) (((__HANDLE__)->Instance->CR1 &(TIM_CR1_DIR)) == (TIM_CR1_DIR)) - -/** - * @brief Set the TIM Prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __PRESC__ specifies the Prescaler new value. - * @retval None - */ -#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__) ((__HANDLE__)->Instance->PSC = (__PRESC__)) - -/** - * @brief Set the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __COUNTER__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNT = (__COUNTER__)) - -/** - * @brief Get the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer counter register (TIMx_CNT) - */ -#define __HAL_TIM_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNT) - -/** - * @brief Set the TIM Autoreload Register value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __AUTORELOAD__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_AUTORELOAD(__HANDLE__, __AUTORELOAD__) \ - do{ \ - (__HANDLE__)->Instance->ARR = (__AUTORELOAD__); \ - (__HANDLE__)->Init.Period = (__AUTORELOAD__); \ - } while(0) - -/** - * @brief Get the TIM Autoreload Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer auto-reload register(TIMx_ARR) - */ -#define __HAL_TIM_GET_AUTORELOAD(__HANDLE__) ((__HANDLE__)->Instance->ARR) - -/** - * @brief Set the TIM Clock Division value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __CKD__ specifies the clock division value. - * This parameter can be one of the following value: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - * @retval None - */ -#define __HAL_TIM_SET_CLOCKDIVISION(__HANDLE__, __CKD__) \ - do{ \ - (__HANDLE__)->Instance->CR1 &= (~TIM_CR1_CKD); \ - (__HANDLE__)->Instance->CR1 |= (__CKD__); \ - (__HANDLE__)->Init.ClockDivision = (__CKD__); \ - } while(0) - -/** - * @brief Get the TIM Clock Division value on runtime. - * @param __HANDLE__ TIM handle. - * @retval The clock division can be one of the following values: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - */ -#define __HAL_TIM_GET_CLOCKDIVISION(__HANDLE__) ((__HANDLE__)->Instance->CR1 & TIM_CR1_CKD) - -/** - * @brief Set the TIM Input Capture prescaler on runtime without calling another time HAL_TIM_IC_ConfigChannel() - * function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __ICPSC__ specifies the Input Capture4 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -#define __HAL_TIM_SET_ICPRESCALER(__HANDLE__, __CHANNEL__, __ICPSC__) \ - do{ \ - TIM_RESET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__), (__ICPSC__)); \ - } while(0) - -/** - * @brief Get the TIM Input Capture prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get input capture 1 prescaler value - * @arg TIM_CHANNEL_2: get input capture 2 prescaler value - * @arg TIM_CHANNEL_3: get input capture 3 prescaler value - * @arg TIM_CHANNEL_4: get input capture 4 prescaler value - * @retval The input capture prescaler can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - */ -#define __HAL_TIM_GET_ICPRESCALER(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC2PSC) >> 8U) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC3PSC) :\ - (((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC4PSC)) >> 8U) - -/** - * @brief Set the TIM Capture Compare Register value on runtime without calling another time ConfigChannel function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __COMPARE__ specifies the Capture Compare register new value. - * @retval None - */ -#define __HAL_TIM_SET_COMPARE(__HANDLE__, __CHANNEL__, __COMPARE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3 = (__COMPARE__)) :\ - ((__HANDLE__)->Instance->CCR4 = (__COMPARE__))) - -/** - * @brief Get the TIM Capture Compare Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channel associated with the capture compare register - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get capture/compare 1 register value - * @arg TIM_CHANNEL_2: get capture/compare 2 register value - * @arg TIM_CHANNEL_3: get capture/compare 3 register value - * @arg TIM_CHANNEL_4: get capture/compare 4 register value - * @retval 16-bit or 32-bit value of the capture/compare register (TIMx_CCRy) - */ -#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3) :\ - ((__HANDLE__)->Instance->CCR4)) - -/** - * @brief Set the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4PE)) - -/** - * @brief Reset the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4PE)) - -/** - * @brief Enable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is enabled an active edge on the trigger input acts - * like a compare match on CCx output. Delay to sample the trigger - * input and to activate CCx output is reduced to 3 clock cycles. - * @note Fast mode acts only if the channel is configured in PWM1 or PWM2 mode. - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4FE)) - -/** - * @brief Disable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is disabled CCx output behaves normally depending - * on counter and CCRx values even when the trigger is ON. The minimum - * delay to activate CCx output when an active edge occurs on the - * trigger input is 5 clock cycles. - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE)) - -/** - * @brief Set the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is set, only counter - * overflow/underflow generates an update interrupt or DMA request (if - * enabled) - * @retval None - */ -#define __HAL_TIM_URS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|= TIM_CR1_URS) - -/** - * @brief Reset the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is reset, any of the - * following events generate an update interrupt or DMA request (if - * enabled): - * _ Counter overflow underflow - * _ Setting the UG bit - * _ Update generation through the slave mode controller - * @retval None - */ -#define __HAL_TIM_URS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1&=~TIM_CR1_URS) - -/** - * @brief Set the TIM Capture x input polarity on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __POLARITY__ Polarity for TIx source - * @arg TIM_INPUTCHANNELPOLARITY_RISING: Rising Edge - * @arg TIM_INPUTCHANNELPOLARITY_FALLING: Falling Edge - * @arg TIM_INPUTCHANNELPOLARITY_BOTHEDGE: Rising and Falling Edge - * @retval None - */ -#define __HAL_TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - do{ \ - TIM_RESET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__), (__POLARITY__)); \ - }while(0) - -/** @brief Select the Capture/compare DMA request source. - * @param __HANDLE__ specifies the TIM Handle. - * @param __CCDMA__ specifies Capture/compare DMA request source - * This parameter can be one of the following values: - * @arg TIM_CCDMAREQUEST_CC: CCx DMA request generated on Capture/Compare event - * @arg TIM_CCDMAREQUEST_UPDATE: CCx DMA request generated on Update event - * @retval None - */ -#define __HAL_TIM_SELECT_CCDMAREQUEST(__HANDLE__, __CCDMA__) \ - MODIFY_REG((__HANDLE__)->Instance->CR2, TIM_CR2_CCDS, (__CCDMA__)) - -/** - * @} - */ -/* End of exported macros ----------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup TIM_Private_Constants TIM Private Constants - * @{ - */ -/* The counter of a timer instance is disabled only if all the CCx and CCxN - channels have been disabled */ -#define TIM_CCER_CCxE_MASK ((uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)) -#define TIM_CCER_CCxNE_MASK ((uint32_t)(TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) -/** - * @} - */ -/* End of private constants --------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup TIM_Private_Macros TIM Private Macros - * @{ - */ -#define IS_TIM_CLEARINPUT_SOURCE(__MODE__) (((__MODE__) == TIM_CLEARINPUTSOURCE_NONE) || \ - ((__MODE__) == TIM_CLEARINPUTSOURCE_ETR)) - -#define IS_TIM_DMA_BASE(__BASE__) (((__BASE__) == TIM_DMABASE_CR1) || \ - ((__BASE__) == TIM_DMABASE_CR2) || \ - ((__BASE__) == TIM_DMABASE_SMCR) || \ - ((__BASE__) == TIM_DMABASE_DIER) || \ - ((__BASE__) == TIM_DMABASE_SR) || \ - ((__BASE__) == TIM_DMABASE_EGR) || \ - ((__BASE__) == TIM_DMABASE_CCMR1) || \ - ((__BASE__) == TIM_DMABASE_CCMR2) || \ - ((__BASE__) == TIM_DMABASE_CCER) || \ - ((__BASE__) == TIM_DMABASE_CNT) || \ - ((__BASE__) == TIM_DMABASE_PSC) || \ - ((__BASE__) == TIM_DMABASE_ARR) || \ - ((__BASE__) == TIM_DMABASE_RCR) || \ - ((__BASE__) == TIM_DMABASE_CCR1) || \ - ((__BASE__) == TIM_DMABASE_CCR2) || \ - ((__BASE__) == TIM_DMABASE_CCR3) || \ - ((__BASE__) == TIM_DMABASE_CCR4) || \ - ((__BASE__) == TIM_DMABASE_BDTR)) - -#define IS_TIM_EVENT_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFFFF00U) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_COUNTER_MODE(__MODE__) (((__MODE__) == TIM_COUNTERMODE_UP) || \ - ((__MODE__) == TIM_COUNTERMODE_DOWN) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED1) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED2) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED3)) - -#define IS_TIM_CLOCKDIVISION_DIV(__DIV__) (((__DIV__) == TIM_CLOCKDIVISION_DIV1) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV2) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV4)) - -#define IS_TIM_AUTORELOAD_PRELOAD(PRELOAD) (((PRELOAD) == TIM_AUTORELOAD_PRELOAD_DISABLE) || \ - ((PRELOAD) == TIM_AUTORELOAD_PRELOAD_ENABLE)) - -#define IS_TIM_FAST_STATE(__STATE__) (((__STATE__) == TIM_OCFAST_DISABLE) || \ - ((__STATE__) == TIM_OCFAST_ENABLE)) - -#define IS_TIM_OC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCPOLARITY_LOW)) - -#define IS_TIM_OCN_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCNPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCNPOLARITY_LOW)) - -#define IS_TIM_OCIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCIDLESTATE_RESET)) - -#define IS_TIM_OCNIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCNIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCNIDLESTATE_RESET)) - -#define IS_TIM_ENCODERINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_FALLING)) - -#define IS_TIM_IC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ICPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_BOTHEDGE)) - -#define IS_TIM_IC_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_ICSELECTION_DIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_INDIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_TRC)) - -#define IS_TIM_IC_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_ICPSC_DIV1) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV2) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV4) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV8)) - -#define IS_TIM_OPM_MODE(__MODE__) (((__MODE__) == TIM_OPMODE_SINGLE) || \ - ((__MODE__) == TIM_OPMODE_REPETITIVE)) - -#define IS_TIM_ENCODER_MODE(__MODE__) (((__MODE__) == TIM_ENCODERMODE_TI1) || \ - ((__MODE__) == TIM_ENCODERMODE_TI2) || \ - ((__MODE__) == TIM_ENCODERMODE_TI12)) - -#define IS_TIM_DMA_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFF80FFU) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3) || \ - ((__CHANNEL__) == TIM_CHANNEL_4) || \ - ((__CHANNEL__) == TIM_CHANNEL_ALL)) - -#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2)) - -#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3)) - -#define IS_TIM_CLOCKSOURCE(__CLOCK__) (((__CLOCK__) == TIM_CLOCKSOURCE_INTERNAL) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1ED) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR0) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR3)) - -#define IS_TIM_CLOCKPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLOCKPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_BOTHEDGE)) - -#define IS_TIM_CLOCKPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV8)) - -#define IS_TIM_CLOCKFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_CLEARINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLEARINPUTPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLEARINPUTPOLARITY_NONINVERTED)) - -#define IS_TIM_CLEARINPUT_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV8)) - -#define IS_TIM_CLEARINPUT_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_OSSR_STATE(__STATE__) (((__STATE__) == TIM_OSSR_ENABLE) || \ - ((__STATE__) == TIM_OSSR_DISABLE)) - -#define IS_TIM_OSSI_STATE(__STATE__) (((__STATE__) == TIM_OSSI_ENABLE) || \ - ((__STATE__) == TIM_OSSI_DISABLE)) - -#define IS_TIM_LOCK_LEVEL(__LEVEL__) (((__LEVEL__) == TIM_LOCKLEVEL_OFF) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_1) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_2) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_3)) - -#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL) - - -#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \ - ((__STATE__) == TIM_BREAK_DISABLE)) - -#define IS_TIM_BREAK_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_BREAKPOLARITY_LOW) || \ - ((__POLARITY__) == TIM_BREAKPOLARITY_HIGH)) - -#define IS_TIM_AUTOMATIC_OUTPUT_STATE(__STATE__) (((__STATE__) == TIM_AUTOMATICOUTPUT_ENABLE) || \ - ((__STATE__) == TIM_AUTOMATICOUTPUT_DISABLE)) - -#define IS_TIM_TRGO_SOURCE(__SOURCE__) (((__SOURCE__) == TIM_TRGO_RESET) || \ - ((__SOURCE__) == TIM_TRGO_ENABLE) || \ - ((__SOURCE__) == TIM_TRGO_UPDATE) || \ - ((__SOURCE__) == TIM_TRGO_OC1) || \ - ((__SOURCE__) == TIM_TRGO_OC1REF) || \ - ((__SOURCE__) == TIM_TRGO_OC2REF) || \ - ((__SOURCE__) == TIM_TRGO_OC3REF) || \ - ((__SOURCE__) == TIM_TRGO_OC4REF)) - -#define IS_TIM_MSM_STATE(__STATE__) (((__STATE__) == TIM_MASTERSLAVEMODE_ENABLE) || \ - ((__STATE__) == TIM_MASTERSLAVEMODE_DISABLE)) - -#define IS_TIM_SLAVE_MODE(__MODE__) (((__MODE__) == TIM_SLAVEMODE_DISABLE) || \ - ((__MODE__) == TIM_SLAVEMODE_RESET) || \ - ((__MODE__) == TIM_SLAVEMODE_GATED) || \ - ((__MODE__) == TIM_SLAVEMODE_TRIGGER) || \ - ((__MODE__) == TIM_SLAVEMODE_EXTERNAL1)) - -#define IS_TIM_PWM_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_PWM1) || \ - ((__MODE__) == TIM_OCMODE_PWM2)) - -#define IS_TIM_OC_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_TIMING) || \ - ((__MODE__) == TIM_OCMODE_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_INACTIVE) || \ - ((__MODE__) == TIM_OCMODE_TOGGLE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_INACTIVE)) - -#define IS_TIM_TRIGGER_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_TI1F_ED) || \ - ((__SELECTION__) == TIM_TS_TI1FP1) || \ - ((__SELECTION__) == TIM_TS_TI2FP2) || \ - ((__SELECTION__) == TIM_TS_ETRF)) - -#define IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_NONE)) - -#define IS_TIM_TRIGGERPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_TRIGGERPOLARITY_INVERTED ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_RISING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_FALLING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_BOTHEDGE )) - -#define IS_TIM_TRIGGERPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV8)) - -#define IS_TIM_TRIGGERFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_TI1SELECTION(__TI1SELECTION__) (((__TI1SELECTION__) == TIM_TI1SELECTION_CH1) || \ - ((__TI1SELECTION__) == TIM_TI1SELECTION_XORCOMBINATION)) - -#define IS_TIM_DMA_LENGTH(__LENGTH__) (((__LENGTH__) == TIM_DMABURSTLENGTH_1TRANSFER) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_2TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_3TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_4TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_5TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_6TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_7TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_8TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_9TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_10TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_11TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_12TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_13TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_14TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_15TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_16TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_17TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_18TRANSFERS)) - -#define IS_TIM_DMA_DATA_LENGTH(LENGTH) (((LENGTH) >= 0x1U) && ((LENGTH) < 0x10000U)) - -#define IS_TIM_IC_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_DEADTIME(__DEADTIME__) ((__DEADTIME__) <= 0xFFU) - -#define IS_TIM_SLAVEMODE_TRIGGER_ENABLED(__TRIGGER__) ((__TRIGGER__) == TIM_SLAVEMODE_TRIGGER) - -#define TIM_SET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__, __ICPSC__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= (__ICPSC__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= ((__ICPSC__) << 8U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= (__ICPSC__)) :\ - ((__HANDLE__)->Instance->CCMR2 |= ((__ICPSC__) << 8U))) - -#define TIM_RESET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC)) - -#define TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER |= (__POLARITY__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 4U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 8U)) :\ - ((__HANDLE__)->Instance->CCER |= (((__POLARITY__) << 12U)))) - -#define TIM_RESET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP)) :\ - ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP))) - -#define TIM_CHANNEL_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelState[2] :\ - (__HANDLE__)->ChannelState[3]) - -#define TIM_CHANNEL_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__); \ - } while(0) - -#define TIM_CHANNEL_N_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelNState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelNState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelNState[2] :\ - (__HANDLE__)->ChannelNState[3]) - -#define TIM_CHANNEL_N_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelNState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelNState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelNState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelNState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_N_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelNState[0] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[1] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[2] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[3] = \ - (__CHANNEL_STATE__); \ - } while(0) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/* Include TIM HAL Extended module */ -#include "stm32f4xx_hal_tim_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIM_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @addtogroup TIM_Exported_Functions_Group1 TIM Time Base functions - * @brief Time Base functions - * @{ - */ -/* Time Base functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group2 TIM Output Compare functions - * @brief TIM Output Compare functions - * @{ - */ -/* Timer Output Compare functions *********************************************/ -HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group3 TIM PWM functions - * @brief TIM PWM functions - * @{ - */ -/* Timer PWM functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group4 TIM Input Capture functions - * @brief TIM Input Capture functions - * @{ - */ -/* Timer Input Capture functions **********************************************/ -HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group5 TIM One Pulse functions - * @brief TIM One Pulse functions - * @{ - */ -/* Timer One Pulse functions **************************************************/ -HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode); -HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group6 TIM Encoder functions - * @brief TIM Encoder functions - * @{ - */ -/* Timer Encoder functions ****************************************************/ -HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, - uint32_t *pData2, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group7 TIM IRQ handler management - * @brief IRQ handler management - * @{ - */ -/* Interrupt Handler functions ***********************************************/ -void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Control functions *********************************************************/ -HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, - uint32_t OutputChannel, uint32_t InputChannel); -HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, TIM_ClearInputConfigTypeDef *sClearInputConfig, - uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig); -HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource); -uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions - * @brief TIM Callbacks functions - * @{ - */ -/* Callback in non blocking modes (Interrupt and DMA) *************************/ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, - pTIM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim); - -/* Peripheral Channel state functions ************************************************/ -HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @defgroup TIM_Private_Functions TIM Private Functions - * @{ - */ -void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure); -void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, uint32_t TIM_ICFilter); -void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, - uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter); - -void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_DMAError(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -void TIM_ResetCallback(TIM_HandleTypeDef *htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_TIM_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim.h + * @author MCD Application Team + * @brief Header file of TIM HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_TIM_H +#define STM32F4xx_HAL_TIM_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup TIM_Exported_Types TIM Exported Types + * @{ + */ + +/** + * @brief TIM Time base Configuration Structure definition + */ +typedef struct +{ + uint32_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ + + uint32_t CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint32_t Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ + + uint32_t ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_ClockDivision */ + + uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + GP timers: this parameter must be a number between Min_Data = 0x00 and + Max_Data = 0xFF. + Advanced timers: this parameter must be a number between Min_Data = 0x0000 and + Max_Data = 0xFFFF. */ + + uint32_t AutoReloadPreload; /*!< Specifies the auto-reload preload. + This parameter can be a value of @ref TIM_AutoReloadPreload */ +} TIM_Base_InitTypeDef; + +/** + * @brief TIM Output Compare Configuration Structure definition + */ +typedef struct +{ + uint32_t OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ + + uint32_t OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for timer instances supporting break feature. */ + + uint32_t OCFastMode; /*!< Specifies the Fast mode state. + This parameter can be a value of @ref TIM_Output_Fast_State + @note This parameter is valid only in PWM1 and PWM2 mode. */ + + + uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for timer instances supporting break feature. */ + + uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for timer instances supporting break feature. */ +} TIM_OC_InitTypeDef; + +/** + * @brief TIM One Pulse Mode Configuration Structure definition + */ +typedef struct +{ + uint32_t OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ + + uint32_t OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for timer instances supporting break feature. */ + + uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for timer instances supporting break feature. */ + + uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for timer instances supporting break feature. */ + + uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint32_t ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint32_t ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ +} TIM_OnePulse_InitTypeDef; + +/** + * @brief TIM Input Capture Configuration Structure definition + */ +typedef struct +{ + uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint32_t ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint32_t ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ +} TIM_IC_InitTypeDef; + +/** + * @brief TIM Encoder Configuration Structure definition + */ +typedef struct +{ + uint32_t EncoderMode; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Encoder_Mode */ + + uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ + + uint32_t IC1Selection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint32_t IC1Filter; /*!< Specifies the input capture filter. + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ + + uint32_t IC2Polarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ + + uint32_t IC2Selection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint32_t IC2Prescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint32_t IC2Filter; /*!< Specifies the input capture filter. + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ +} TIM_Encoder_InitTypeDef; + +/** + * @brief Clock Configuration Handle Structure definition + */ +typedef struct +{ + uint32_t ClockSource; /*!< TIM clock sources + This parameter can be a value of @ref TIM_Clock_Source */ + uint32_t ClockPolarity; /*!< TIM clock polarity + This parameter can be a value of @ref TIM_Clock_Polarity */ + uint32_t ClockPrescaler; /*!< TIM clock prescaler + This parameter can be a value of @ref TIM_Clock_Prescaler */ + uint32_t ClockFilter; /*!< TIM clock filter + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ +} TIM_ClockConfigTypeDef; + +/** + * @brief TIM Clear Input Configuration Handle Structure definition + */ +typedef struct +{ + uint32_t ClearInputState; /*!< TIM clear Input state + This parameter can be ENABLE or DISABLE */ + uint32_t ClearInputSource; /*!< TIM clear Input sources + This parameter can be a value of @ref TIM_ClearInput_Source */ + uint32_t ClearInputPolarity; /*!< TIM Clear Input polarity + This parameter can be a value of @ref TIM_ClearInput_Polarity */ + uint32_t ClearInputPrescaler; /*!< TIM Clear Input prescaler + This parameter must be 0: When OCRef clear feature is used with ETR source, + ETR prescaler must be off */ + uint32_t ClearInputFilter; /*!< TIM Clear Input filter + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ +} TIM_ClearInputConfigTypeDef; + +/** + * @brief TIM Master configuration Structure definition + */ +typedef struct +{ + uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection + This parameter can be a value of @ref TIM_Master_Mode_Selection */ + uint32_t MasterSlaveMode; /*!< Master/slave mode selection + This parameter can be a value of @ref TIM_Master_Slave_Mode + @note When the Master/slave mode is enabled, the effect of + an event on the trigger input (TRGI) is delayed to allow a + perfect synchronization between the current timer and its + slaves (through TRGO). It is not mandatory in case of timer + synchronization mode. */ +} TIM_MasterConfigTypeDef; + +/** + * @brief TIM Slave configuration Structure definition + */ +typedef struct +{ + uint32_t SlaveMode; /*!< Slave mode selection + This parameter can be a value of @ref TIM_Slave_Mode */ + uint32_t InputTrigger; /*!< Input Trigger source + This parameter can be a value of @ref TIM_Trigger_Selection */ + uint32_t TriggerPolarity; /*!< Input Trigger polarity + This parameter can be a value of @ref TIM_Trigger_Polarity */ + uint32_t TriggerPrescaler; /*!< Input trigger prescaler + This parameter can be a value of @ref TIM_Trigger_Prescaler */ + uint32_t TriggerFilter; /*!< Input trigger filter + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ + +} TIM_SlaveConfigTypeDef; + +/** + * @brief TIM Break input(s) and Dead time configuration Structure definition + * @note 2 break inputs can be configured (BKIN and BKIN2) with configurable + * filter and polarity. + */ +typedef struct +{ + uint32_t OffStateRunMode; /*!< TIM off state in run mode, This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ + + uint32_t OffStateIDLEMode; /*!< TIM off state in IDLE mode, This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint32_t LockLevel; /*!< TIM Lock level, This parameter can be a value of @ref TIM_Lock_level */ + + uint32_t DeadTime; /*!< TIM dead Time, This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF */ + + uint32_t BreakState; /*!< TIM Break State, This parameter can be a value of @ref TIM_Break_Input_enable_disable */ + + uint32_t BreakPolarity; /*!< TIM Break input polarity, This parameter can be a value of @ref TIM_Break_Polarity */ + + uint32_t BreakFilter; /*!< Specifies the break input filter.This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ + + uint32_t AutomaticOutput; /*!< TIM Automatic Output Enable state, This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ + +} TIM_BreakDeadTimeConfigTypeDef; + +/** + * @brief HAL State structures definition + */ +typedef enum +{ + HAL_TIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ + HAL_TIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ + HAL_TIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ + HAL_TIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ + HAL_TIM_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ +} HAL_TIM_StateTypeDef; + +/** + * @brief TIM Channel States definition + */ +typedef enum +{ + HAL_TIM_CHANNEL_STATE_RESET = 0x00U, /*!< TIM Channel initial state */ + HAL_TIM_CHANNEL_STATE_READY = 0x01U, /*!< TIM Channel ready for use */ + HAL_TIM_CHANNEL_STATE_BUSY = 0x02U, /*!< An internal process is ongoing on the TIM channel */ +} HAL_TIM_ChannelStateTypeDef; + +/** + * @brief DMA Burst States definition + */ +typedef enum +{ + HAL_DMA_BURST_STATE_RESET = 0x00U, /*!< DMA Burst initial state */ + HAL_DMA_BURST_STATE_READY = 0x01U, /*!< DMA Burst ready for use */ + HAL_DMA_BURST_STATE_BUSY = 0x02U, /*!< Ongoing DMA Burst */ +} HAL_TIM_DMABurstStateTypeDef; + +/** + * @brief HAL Active channel structures definition + */ +typedef enum +{ + HAL_TIM_ACTIVE_CHANNEL_1 = 0x01U, /*!< The active channel is 1 */ + HAL_TIM_ACTIVE_CHANNEL_2 = 0x02U, /*!< The active channel is 2 */ + HAL_TIM_ACTIVE_CHANNEL_3 = 0x04U, /*!< The active channel is 3 */ + HAL_TIM_ACTIVE_CHANNEL_4 = 0x08U, /*!< The active channel is 4 */ + HAL_TIM_ACTIVE_CHANNEL_CLEARED = 0x00U /*!< All active channels cleared */ +} HAL_TIM_ActiveChannel; + +/** + * @brief TIM Time Base Handle Structure definition + */ +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +typedef struct __TIM_HandleTypeDef +#else +typedef struct +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +{ + TIM_TypeDef *Instance; /*!< Register base address */ + TIM_Base_InitTypeDef Init; /*!< TIM Time Base required parameters */ + HAL_TIM_ActiveChannel Channel; /*!< Active channel */ + DMA_HandleTypeDef *hdma[7]; /*!< DMA Handlers array + This array is accessed by a @ref DMA_Handle_index */ + HAL_LockTypeDef Lock; /*!< Locking object */ + __IO HAL_TIM_StateTypeDef State; /*!< TIM operation state */ + __IO HAL_TIM_ChannelStateTypeDef ChannelState[4]; /*!< TIM channel operation state */ + __IO HAL_TIM_ChannelStateTypeDef ChannelNState[4]; /*!< TIM complementary channel operation state */ + __IO HAL_TIM_DMABurstStateTypeDef DMABurstState; /*!< DMA burst operation state */ + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + void (* Base_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp Init Callback */ + void (* Base_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp DeInit Callback */ + void (* IC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp Init Callback */ + void (* IC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp DeInit Callback */ + void (* OC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp Init Callback */ + void (* OC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp DeInit Callback */ + void (* PWM_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp Init Callback */ + void (* PWM_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp DeInit Callback */ + void (* OnePulse_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp Init Callback */ + void (* OnePulse_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp DeInit Callback */ + void (* Encoder_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp Init Callback */ + void (* Encoder_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp DeInit Callback */ + void (* HallSensor_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp Init Callback */ + void (* HallSensor_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp DeInit Callback */ + void (* PeriodElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed Callback */ + void (* PeriodElapsedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed half complete Callback */ + void (* TriggerCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger Callback */ + void (* TriggerHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger half complete Callback */ + void (* IC_CaptureCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture Callback */ + void (* IC_CaptureHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture half complete Callback */ + void (* OC_DelayElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Output Compare Delay Elapsed Callback */ + void (* PWM_PulseFinishedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished Callback */ + void (* PWM_PulseFinishedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished half complete Callback */ + void (* ErrorCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Error Callback */ + void (* CommutationCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation Callback */ + void (* CommutationHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation half complete Callback */ + void (* BreakCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Break Callback */ +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} TIM_HandleTypeDef; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +/** + * @brief HAL TIM Callback ID enumeration definition + */ +typedef enum +{ + HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */ + , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */ + , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */ + , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */ + , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */ + , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */ + , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */ + , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */ + , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */ + , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */ + , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */ + , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */ + , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */ + , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */ + , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */ + , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */ + , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */ + , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */ + + , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */ + , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */ + , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */ + , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */ + , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */ + , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */ + , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */ + , HAL_TIM_COMMUTATION_HALF_CB_ID = 0x19U /*!< TIM Commutation half complete Callback ID */ + , HAL_TIM_BREAK_CB_ID = 0x1AU /*!< TIM Break Callback ID */ +} HAL_TIM_CallbackIDTypeDef; + +/** + * @brief HAL TIM Callback pointer definition + */ +typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to the TIM callback function */ + +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ +/* End of exported types -----------------------------------------------------*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup TIM_Exported_Constants TIM Exported Constants + * @{ + */ + +/** @defgroup TIM_ClearInput_Source TIM Clear Input Source + * @{ + */ +#define TIM_CLEARINPUTSOURCE_NONE 0x00000000U /*!< OCREF_CLR is disabled */ +#define TIM_CLEARINPUTSOURCE_ETR 0x00000001U /*!< OCREF_CLR is connected to ETRF input */ +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address TIM DMA Base Address + * @{ + */ +#define TIM_DMABASE_CR1 0x00000000U +#define TIM_DMABASE_CR2 0x00000001U +#define TIM_DMABASE_SMCR 0x00000002U +#define TIM_DMABASE_DIER 0x00000003U +#define TIM_DMABASE_SR 0x00000004U +#define TIM_DMABASE_EGR 0x00000005U +#define TIM_DMABASE_CCMR1 0x00000006U +#define TIM_DMABASE_CCMR2 0x00000007U +#define TIM_DMABASE_CCER 0x00000008U +#define TIM_DMABASE_CNT 0x00000009U +#define TIM_DMABASE_PSC 0x0000000AU +#define TIM_DMABASE_ARR 0x0000000BU +#define TIM_DMABASE_RCR 0x0000000CU +#define TIM_DMABASE_CCR1 0x0000000DU +#define TIM_DMABASE_CCR2 0x0000000EU +#define TIM_DMABASE_CCR3 0x0000000FU +#define TIM_DMABASE_CCR4 0x00000010U +#define TIM_DMABASE_BDTR 0x00000011U +#define TIM_DMABASE_DCR 0x00000012U +#define TIM_DMABASE_DMAR 0x00000013U +/** + * @} + */ + +/** @defgroup TIM_Event_Source TIM Event Source + * @{ + */ +#define TIM_EVENTSOURCE_UPDATE TIM_EGR_UG /*!< Reinitialize the counter and generates an update of the registers */ +#define TIM_EVENTSOURCE_CC1 TIM_EGR_CC1G /*!< A capture/compare event is generated on channel 1 */ +#define TIM_EVENTSOURCE_CC2 TIM_EGR_CC2G /*!< A capture/compare event is generated on channel 2 */ +#define TIM_EVENTSOURCE_CC3 TIM_EGR_CC3G /*!< A capture/compare event is generated on channel 3 */ +#define TIM_EVENTSOURCE_CC4 TIM_EGR_CC4G /*!< A capture/compare event is generated on channel 4 */ +#define TIM_EVENTSOURCE_COM TIM_EGR_COMG /*!< A commutation event is generated */ +#define TIM_EVENTSOURCE_TRIGGER TIM_EGR_TG /*!< A trigger event is generated */ +#define TIM_EVENTSOURCE_BREAK TIM_EGR_BG /*!< A break event is generated */ +/** + * @} + */ + +/** @defgroup TIM_Input_Channel_Polarity TIM Input Channel polarity + * @{ + */ +#define TIM_INPUTCHANNELPOLARITY_RISING 0x00000000U /*!< Polarity for TIx source */ +#define TIM_INPUTCHANNELPOLARITY_FALLING TIM_CCER_CC1P /*!< Polarity for TIx source */ +#define TIM_INPUTCHANNELPOLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< Polarity for TIx source */ +/** + * @} + */ + +/** @defgroup TIM_ETR_Polarity TIM ETR Polarity + * @{ + */ +#define TIM_ETRPOLARITY_INVERTED TIM_SMCR_ETP /*!< Polarity for ETR source */ +#define TIM_ETRPOLARITY_NONINVERTED 0x00000000U /*!< Polarity for ETR source */ +/** + * @} + */ + +/** @defgroup TIM_ETR_Prescaler TIM ETR Prescaler + * @{ + */ +#define TIM_ETRPRESCALER_DIV1 0x00000000U /*!< No prescaler is used */ +#define TIM_ETRPRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR input source is divided by 2 */ +#define TIM_ETRPRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR input source is divided by 4 */ +#define TIM_ETRPRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR input source is divided by 8 */ +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode TIM Counter Mode + * @{ + */ +#define TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as up-counter */ +#define TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as down-counter */ +#define TIM_COUNTERMODE_CENTERALIGNED1 TIM_CR1_CMS_0 /*!< Center-aligned mode 1 */ +#define TIM_COUNTERMODE_CENTERALIGNED2 TIM_CR1_CMS_1 /*!< Center-aligned mode 2 */ +#define TIM_COUNTERMODE_CENTERALIGNED3 TIM_CR1_CMS /*!< Center-aligned mode 3 */ +/** + * @} + */ + +/** @defgroup TIM_ClockDivision TIM Clock Division + * @{ + */ +#define TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< Clock division: tDTS=tCK_INT */ +#define TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< Clock division: tDTS=2*tCK_INT */ +#define TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< Clock division: tDTS=4*tCK_INT */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_State TIM Output Compare State + * @{ + */ +#define TIM_OUTPUTSTATE_DISABLE 0x00000000U /*!< Capture/Compare 1 output disabled */ +#define TIM_OUTPUTSTATE_ENABLE TIM_CCER_CC1E /*!< Capture/Compare 1 output enabled */ +/** + * @} + */ + +/** @defgroup TIM_AutoReloadPreload TIM Auto-Reload Preload + * @{ + */ +#define TIM_AUTORELOAD_PRELOAD_DISABLE 0x00000000U /*!< TIMx_ARR register is not buffered */ +#define TIM_AUTORELOAD_PRELOAD_ENABLE TIM_CR1_ARPE /*!< TIMx_ARR register is buffered */ + +/** + * @} + */ + +/** @defgroup TIM_Output_Fast_State TIM Output Fast State + * @{ + */ +#define TIM_OCFAST_DISABLE 0x00000000U /*!< Output Compare fast disable */ +#define TIM_OCFAST_ENABLE TIM_CCMR1_OC1FE /*!< Output Compare fast enable */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_State TIM Complementary Output Compare State + * @{ + */ +#define TIM_OUTPUTNSTATE_DISABLE 0x00000000U /*!< OCxN is disabled */ +#define TIM_OUTPUTNSTATE_ENABLE TIM_CCER_CC1NE /*!< OCxN is enabled */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity TIM Output Compare Polarity + * @{ + */ +#define TIM_OCPOLARITY_HIGH 0x00000000U /*!< Capture/Compare output polarity */ +#define TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< Capture/Compare output polarity */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity TIM Complementary Output Compare Polarity + * @{ + */ +#define TIM_OCNPOLARITY_HIGH 0x00000000U /*!< Capture/Compare complementary output polarity */ +#define TIM_OCNPOLARITY_LOW TIM_CCER_CC1NP /*!< Capture/Compare complementary output polarity */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State TIM Output Compare Idle State + * @{ + */ +#define TIM_OCIDLESTATE_SET TIM_CR2_OIS1 /*!< Output Idle state: OCx=1 when MOE=0 */ +#define TIM_OCIDLESTATE_RESET 0x00000000U /*!< Output Idle state: OCx=0 when MOE=0 */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State TIM Complementary Output Compare Idle State + * @{ + */ +#define TIM_OCNIDLESTATE_SET TIM_CR2_OIS1N /*!< Complementary output Idle state: OCxN=1 when MOE=0 */ +#define TIM_OCNIDLESTATE_RESET 0x00000000U /*!< Complementary output Idle state: OCxN=0 when MOE=0 */ +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity TIM Input Capture Polarity + * @{ + */ +#define TIM_ICPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Capture triggered by rising edge on timer input */ +#define TIM_ICPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Capture triggered by falling edge on timer input */ +#define TIM_ICPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Capture triggered by both rising and falling edges on timer input*/ +/** + * @} + */ + +/** @defgroup TIM_Encoder_Input_Polarity TIM Encoder Input Polarity + * @{ + */ +#define TIM_ENCODERINPUTPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Encoder input with rising edge polarity */ +#define TIM_ENCODERINPUTPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Encoder input with falling edge polarity */ +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection TIM Input Capture Selection + * @{ + */ +#define TIM_ICSELECTION_DIRECTTI TIM_CCMR1_CC1S_0 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSELECTION_INDIRECTTI TIM_CCMR1_CC1S_1 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC2, IC1, IC4 or IC3, respectively */ +#define TIM_ICSELECTION_TRC TIM_CCMR1_CC1S /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC */ +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler TIM Input Capture Prescaler + * @{ + */ +#define TIM_ICPSC_DIV1 0x00000000U /*!< Capture performed each time an edge is detected on the capture input */ +#define TIM_ICPSC_DIV2 TIM_CCMR1_IC1PSC_0 /*!< Capture performed once every 2 events */ +#define TIM_ICPSC_DIV4 TIM_CCMR1_IC1PSC_1 /*!< Capture performed once every 4 events */ +#define TIM_ICPSC_DIV8 TIM_CCMR1_IC1PSC /*!< Capture performed once every 8 events */ +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode TIM One Pulse Mode + * @{ + */ +#define TIM_OPMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ +#define TIM_OPMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode TIM Encoder Mode + * @{ + */ +#define TIM_ENCODERMODE_TI1 TIM_SMCR_SMS_0 /*!< Quadrature encoder mode 1, x2 mode, counts up/down on TI1FP1 edge depending on TI2FP2 level */ +#define TIM_ENCODERMODE_TI2 TIM_SMCR_SMS_1 /*!< Quadrature encoder mode 2, x2 mode, counts up/down on TI2FP2 edge depending on TI1FP1 level. */ +#define TIM_ENCODERMODE_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Quadrature encoder mode 3, x4 mode, counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input. */ +/** + * @} + */ + +/** @defgroup TIM_Interrupt_definition TIM interrupt Definition + * @{ + */ +#define TIM_IT_UPDATE TIM_DIER_UIE /*!< Update interrupt */ +#define TIM_IT_CC1 TIM_DIER_CC1IE /*!< Capture/Compare 1 interrupt */ +#define TIM_IT_CC2 TIM_DIER_CC2IE /*!< Capture/Compare 2 interrupt */ +#define TIM_IT_CC3 TIM_DIER_CC3IE /*!< Capture/Compare 3 interrupt */ +#define TIM_IT_CC4 TIM_DIER_CC4IE /*!< Capture/Compare 4 interrupt */ +#define TIM_IT_COM TIM_DIER_COMIE /*!< Commutation interrupt */ +#define TIM_IT_TRIGGER TIM_DIER_TIE /*!< Trigger interrupt */ +#define TIM_IT_BREAK TIM_DIER_BIE /*!< Break interrupt */ +/** + * @} + */ + +/** @defgroup TIM_Commutation_Source TIM Commutation Source + * @{ + */ +#define TIM_COMMUTATION_TRGI TIM_CR2_CCUS /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit or when an rising edge occurs on trigger input */ +#define TIM_COMMUTATION_SOFTWARE 0x00000000U /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit */ +/** + * @} + */ + +/** @defgroup TIM_DMA_sources TIM DMA Sources + * @{ + */ +#define TIM_DMA_UPDATE TIM_DIER_UDE /*!< DMA request is triggered by the update event */ +#define TIM_DMA_CC1 TIM_DIER_CC1DE /*!< DMA request is triggered by the capture/compare macth 1 event */ +#define TIM_DMA_CC2 TIM_DIER_CC2DE /*!< DMA request is triggered by the capture/compare macth 2 event event */ +#define TIM_DMA_CC3 TIM_DIER_CC3DE /*!< DMA request is triggered by the capture/compare macth 3 event event */ +#define TIM_DMA_CC4 TIM_DIER_CC4DE /*!< DMA request is triggered by the capture/compare macth 4 event event */ +#define TIM_DMA_COM TIM_DIER_COMDE /*!< DMA request is triggered by the commutation event */ +#define TIM_DMA_TRIGGER TIM_DIER_TDE /*!< DMA request is triggered by the trigger event */ +/** + * @} + */ + +/** @defgroup TIM_CC_DMA_Request CCx DMA request selection + * @{ + */ +#define TIM_CCDMAREQUEST_CC 0x00000000U /*!< CCx DMA request sent when capture or compare match event occurs */ +#define TIM_CCDMAREQUEST_UPDATE TIM_CR2_CCDS /*!< CCx DMA requests sent when update event occurs */ +/** + * @} + */ + +/** @defgroup TIM_Flag_definition TIM Flag Definition + * @{ + */ +#define TIM_FLAG_UPDATE TIM_SR_UIF /*!< Update interrupt flag */ +#define TIM_FLAG_CC1 TIM_SR_CC1IF /*!< Capture/Compare 1 interrupt flag */ +#define TIM_FLAG_CC2 TIM_SR_CC2IF /*!< Capture/Compare 2 interrupt flag */ +#define TIM_FLAG_CC3 TIM_SR_CC3IF /*!< Capture/Compare 3 interrupt flag */ +#define TIM_FLAG_CC4 TIM_SR_CC4IF /*!< Capture/Compare 4 interrupt flag */ +#define TIM_FLAG_COM TIM_SR_COMIF /*!< Commutation interrupt flag */ +#define TIM_FLAG_TRIGGER TIM_SR_TIF /*!< Trigger interrupt flag */ +#define TIM_FLAG_BREAK TIM_SR_BIF /*!< Break interrupt flag */ +#define TIM_FLAG_CC1OF TIM_SR_CC1OF /*!< Capture 1 overcapture flag */ +#define TIM_FLAG_CC2OF TIM_SR_CC2OF /*!< Capture 2 overcapture flag */ +#define TIM_FLAG_CC3OF TIM_SR_CC3OF /*!< Capture 3 overcapture flag */ +#define TIM_FLAG_CC4OF TIM_SR_CC4OF /*!< Capture 4 overcapture flag */ +/** + * @} + */ + +/** @defgroup TIM_Channel TIM Channel + * @{ + */ +#define TIM_CHANNEL_1 0x00000000U /*!< Capture/compare channel 1 identifier */ +#define TIM_CHANNEL_2 0x00000004U /*!< Capture/compare channel 2 identifier */ +#define TIM_CHANNEL_3 0x00000008U /*!< Capture/compare channel 3 identifier */ +#define TIM_CHANNEL_4 0x0000000CU /*!< Capture/compare channel 4 identifier */ +#define TIM_CHANNEL_ALL 0x0000003CU /*!< Global Capture/compare channel identifier */ +/** + * @} + */ + +/** @defgroup TIM_Clock_Source TIM Clock Source + * @{ + */ +#define TIM_CLOCKSOURCE_INTERNAL TIM_SMCR_ETPS_0 /*!< Internal clock source */ +#define TIM_CLOCKSOURCE_ETRMODE1 TIM_TS_ETRF /*!< External clock source mode 1 (ETRF) */ +#define TIM_CLOCKSOURCE_ETRMODE2 TIM_SMCR_ETPS_1 /*!< External clock source mode 2 */ +#define TIM_CLOCKSOURCE_TI1ED TIM_TS_TI1F_ED /*!< External clock source mode 1 (TTI1FP1 + edge detect.) */ +#define TIM_CLOCKSOURCE_TI1 TIM_TS_TI1FP1 /*!< External clock source mode 1 (TTI1FP1) */ +#define TIM_CLOCKSOURCE_TI2 TIM_TS_TI2FP2 /*!< External clock source mode 1 (TTI2FP2) */ +#define TIM_CLOCKSOURCE_ITR0 TIM_TS_ITR0 /*!< External clock source mode 1 (ITR0) */ +#define TIM_CLOCKSOURCE_ITR1 TIM_TS_ITR1 /*!< External clock source mode 1 (ITR1) */ +#define TIM_CLOCKSOURCE_ITR2 TIM_TS_ITR2 /*!< External clock source mode 1 (ITR2) */ +#define TIM_CLOCKSOURCE_ITR3 TIM_TS_ITR3 /*!< External clock source mode 1 (ITR3) */ +/** + * @} + */ + +/** @defgroup TIM_Clock_Polarity TIM Clock Polarity + * @{ + */ +#define TIM_CLOCKPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx clock sources */ +#define TIM_CLOCKPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx clock sources */ +#define TIM_CLOCKPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIx clock sources */ +#define TIM_CLOCKPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIx clock sources */ +#define TIM_CLOCKPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIx clock sources */ +/** + * @} + */ + +/** @defgroup TIM_Clock_Prescaler TIM Clock Prescaler + * @{ + */ +#define TIM_CLOCKPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ +#define TIM_CLOCKPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Clock: Capture performed once every 2 events. */ +#define TIM_CLOCKPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Clock: Capture performed once every 4 events. */ +#define TIM_CLOCKPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Clock: Capture performed once every 8 events. */ +/** + * @} + */ + +/** @defgroup TIM_ClearInput_Polarity TIM Clear Input Polarity + * @{ + */ +#define TIM_CLEARINPUTPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx pin */ +#define TIM_CLEARINPUTPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx pin */ +/** + * @} + */ + +/** @defgroup TIM_ClearInput_Prescaler TIM Clear Input Prescaler + * @{ + */ +#define TIM_CLEARINPUTPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ +#define TIM_CLEARINPUTPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR pin: Capture performed once every 2 events. */ +#define TIM_CLEARINPUTPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR pin: Capture performed once every 4 events. */ +#define TIM_CLEARINPUTPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR pin: Capture performed once every 8 events. */ +/** + * @} + */ + +/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state TIM OSSR OffState Selection for Run mode state + * @{ + */ +#define TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ +#define TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ +/** + * @} + */ + +/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state TIM OSSI OffState Selection for Idle mode state + * @{ + */ +#define TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ +#define TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ +/** + * @} + */ +/** @defgroup TIM_Lock_level TIM Lock level + * @{ + */ +#define TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF */ +#define TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */ +#define TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */ +#define TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */ +/** + * @} + */ + +/** @defgroup TIM_Break_Input_enable_disable TIM Break Input Enable + * @{ + */ +#define TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break input BRK is enabled */ +#define TIM_BREAK_DISABLE 0x00000000U /*!< Break input BRK is disabled */ +/** + * @} + */ + +/** @defgroup TIM_Break_Polarity TIM Break Input Polarity + * @{ + */ +#define TIM_BREAKPOLARITY_LOW 0x00000000U /*!< Break input BRK is active low */ +#define TIM_BREAKPOLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */ +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset TIM Automatic Output Enable + * @{ + */ +#define TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ +#define TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event (if none of the break inputs BRK and BRK2 is active) */ +/** + * @} + */ + +/** @defgroup TIM_Master_Mode_Selection TIM Master Mode Selection + * @{ + */ +#define TIM_TRGO_RESET 0x00000000U /*!< TIMx_EGR.UG bit is used as trigger output (TRGO) */ +#define TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< TIMx_CR1.CEN bit is used as trigger output (TRGO) */ +#define TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output (TRGO) */ +#define TIM_TRGO_OC1 (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< Capture or a compare match 1 is used as trigger output (TRGO) */ +#define TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output (TRGO) */ +#define TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output(TRGO) */ +#define TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output(TRGO) */ +#define TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output(TRGO) */ +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode TIM Master/Slave Mode + * @{ + */ +#define TIM_MASTERSLAVEMODE_ENABLE TIM_SMCR_MSM /*!< No action */ +#define TIM_MASTERSLAVEMODE_DISABLE 0x00000000U /*!< Master/slave mode is selected */ +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode TIM Slave mode + * @{ + */ +#define TIM_SLAVEMODE_DISABLE 0x00000000U /*!< Slave mode disabled */ +#define TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode */ +#define TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode */ +#define TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode */ +#define TIM_SLAVEMODE_EXTERNAL1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< External Clock Mode 1 */ +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_and_PWM_modes TIM Output Compare and PWM Modes + * @{ + */ +#define TIM_OCMODE_TIMING 0x00000000U /*!< Frozen */ +#define TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!< Set channel to active level on match */ +#define TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!< Set channel to inactive level on match */ +#define TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< Toggle */ +#define TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!< PWM mode 1 */ +#define TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< PWM mode 2 */ +#define TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!< Force active level */ +#define TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!< Force inactive level */ +/** + * @} + */ + +/** @defgroup TIM_Trigger_Selection TIM Trigger Selection + * @{ + */ +#define TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) */ +#define TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) */ +#define TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) */ +#define TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) */ +#define TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) */ +#define TIM_TS_TI1FP1 (TIM_SMCR_TS_0 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 1 (TI1FP1) */ +#define TIM_TS_TI2FP2 (TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 2 (TI2FP2) */ +#define TIM_TS_ETRF (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered External Trigger input (ETRF) */ +#define TIM_TS_NONE 0x0000FFFFU /*!< No trigger selected */ +/** + * @} + */ + +/** @defgroup TIM_Trigger_Polarity TIM Trigger Polarity + * @{ + */ +#define TIM_TRIGGERPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx trigger sources */ +#define TIM_TRIGGERPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx trigger sources */ +#define TIM_TRIGGERPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ +#define TIM_TRIGGERPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ +#define TIM_TRIGGERPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIxFPx or TI1_ED trigger sources */ +/** + * @} + */ + +/** @defgroup TIM_Trigger_Prescaler TIM Trigger Prescaler + * @{ + */ +#define TIM_TRIGGERPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ +#define TIM_TRIGGERPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Trigger: Capture performed once every 2 events. */ +#define TIM_TRIGGERPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Trigger: Capture performed once every 4 events. */ +#define TIM_TRIGGERPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Trigger: Capture performed once every 8 events. */ +/** + * @} + */ + +/** @defgroup TIM_TI1_Selection TIM TI1 Input Selection + * @{ + */ +#define TIM_TI1SELECTION_CH1 0x00000000U /*!< The TIMx_CH1 pin is connected to TI1 input */ +#define TIM_TI1SELECTION_XORCOMBINATION TIM_CR2_TI1S /*!< The TIMx_CH1, CH2 and CH3 pins are connected to the TI1 input (XOR combination) */ +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length TIM DMA Burst Length + * @{ + */ +#define TIM_DMABURSTLENGTH_1TRANSFER 0x00000000U /*!< The transfer is done to 1 register starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_2TRANSFERS 0x00000100U /*!< The transfer is done to 2 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_3TRANSFERS 0x00000200U /*!< The transfer is done to 3 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_4TRANSFERS 0x00000300U /*!< The transfer is done to 4 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_5TRANSFERS 0x00000400U /*!< The transfer is done to 5 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_6TRANSFERS 0x00000500U /*!< The transfer is done to 6 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_7TRANSFERS 0x00000600U /*!< The transfer is done to 7 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_8TRANSFERS 0x00000700U /*!< The transfer is done to 8 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_9TRANSFERS 0x00000800U /*!< The transfer is done to 9 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_10TRANSFERS 0x00000900U /*!< The transfer is done to 10 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_11TRANSFERS 0x00000A00U /*!< The transfer is done to 11 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_12TRANSFERS 0x00000B00U /*!< The transfer is done to 12 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_13TRANSFERS 0x00000C00U /*!< The transfer is done to 13 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_14TRANSFERS 0x00000D00U /*!< The transfer is done to 14 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_15TRANSFERS 0x00000E00U /*!< The transfer is done to 15 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_16TRANSFERS 0x00000F00U /*!< The transfer is done to 16 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_17TRANSFERS 0x00001000U /*!< The transfer is done to 17 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +#define TIM_DMABURSTLENGTH_18TRANSFERS 0x00001100U /*!< The transfer is done to 18 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ +/** + * @} + */ + +/** @defgroup DMA_Handle_index TIM DMA Handle Index + * @{ + */ +#define TIM_DMA_ID_UPDATE ((uint16_t) 0x0000) /*!< Index of the DMA handle used for Update DMA requests */ +#define TIM_DMA_ID_CC1 ((uint16_t) 0x0001) /*!< Index of the DMA handle used for Capture/Compare 1 DMA requests */ +#define TIM_DMA_ID_CC2 ((uint16_t) 0x0002) /*!< Index of the DMA handle used for Capture/Compare 2 DMA requests */ +#define TIM_DMA_ID_CC3 ((uint16_t) 0x0003) /*!< Index of the DMA handle used for Capture/Compare 3 DMA requests */ +#define TIM_DMA_ID_CC4 ((uint16_t) 0x0004) /*!< Index of the DMA handle used for Capture/Compare 4 DMA requests */ +#define TIM_DMA_ID_COMMUTATION ((uint16_t) 0x0005) /*!< Index of the DMA handle used for Commutation DMA requests */ +#define TIM_DMA_ID_TRIGGER ((uint16_t) 0x0006) /*!< Index of the DMA handle used for Trigger DMA requests */ +/** + * @} + */ + +/** @defgroup Channel_CC_State TIM Capture/Compare Channel State + * @{ + */ +#define TIM_CCx_ENABLE 0x00000001U /*!< Input or output channel is enabled */ +#define TIM_CCx_DISABLE 0x00000000U /*!< Input or output channel is disabled */ +#define TIM_CCxN_ENABLE 0x00000004U /*!< Complementary output channel is enabled */ +#define TIM_CCxN_DISABLE 0x00000000U /*!< Complementary output channel is enabled */ +/** + * @} + */ + +/** + * @} + */ +/* End of exported constants -------------------------------------------------*/ + +/* Exported macros -----------------------------------------------------------*/ +/** @defgroup TIM_Exported_Macros TIM Exported Macros + * @{ + */ + +/** @brief Reset TIM handle state. + * @param __HANDLE__ TIM handle. + * @retval None + */ +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ + (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ + (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ + (__HANDLE__)->Base_MspInitCallback = NULL; \ + (__HANDLE__)->Base_MspDeInitCallback = NULL; \ + (__HANDLE__)->IC_MspInitCallback = NULL; \ + (__HANDLE__)->IC_MspDeInitCallback = NULL; \ + (__HANDLE__)->OC_MspInitCallback = NULL; \ + (__HANDLE__)->OC_MspDeInitCallback = NULL; \ + (__HANDLE__)->PWM_MspInitCallback = NULL; \ + (__HANDLE__)->PWM_MspDeInitCallback = NULL; \ + (__HANDLE__)->OnePulse_MspInitCallback = NULL; \ + (__HANDLE__)->OnePulse_MspDeInitCallback = NULL; \ + (__HANDLE__)->Encoder_MspInitCallback = NULL; \ + (__HANDLE__)->Encoder_MspDeInitCallback = NULL; \ + (__HANDLE__)->HallSensor_MspInitCallback = NULL; \ + (__HANDLE__)->HallSensor_MspDeInitCallback = NULL; \ + } while(0) +#else +#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ + (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ + (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ + (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ + } while(0) +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @brief Enable the TIM peripheral. + * @param __HANDLE__ TIM handle + * @retval None + */ +#define __HAL_TIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|=(TIM_CR1_CEN)) + +/** + * @brief Enable the TIM main Output. + * @param __HANDLE__ TIM handle + * @retval None + */ +#define __HAL_TIM_MOE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->BDTR|=(TIM_BDTR_MOE)) + +/** + * @brief Disable the TIM peripheral. + * @param __HANDLE__ TIM handle + * @retval None + */ +#define __HAL_TIM_DISABLE(__HANDLE__) \ + do { \ + if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ + { \ + if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ + { \ + (__HANDLE__)->Instance->CR1 &= ~(TIM_CR1_CEN); \ + } \ + } \ + } while(0) + +/** + * @brief Disable the TIM main Output. + * @param __HANDLE__ TIM handle + * @retval None + * @note The Main Output Enable of a timer instance is disabled only if all the CCx and CCxN channels have been + * disabled + */ +#define __HAL_TIM_MOE_DISABLE(__HANDLE__) \ + do { \ + if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ + { \ + if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ + { \ + (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE); \ + } \ + } \ + } while(0) + +/** + * @brief Disable the TIM main Output. + * @param __HANDLE__ TIM handle + * @retval None + * @note The Main Output Enable of a timer instance is disabled unconditionally + */ +#define __HAL_TIM_MOE_DISABLE_UNCONDITIONALLY(__HANDLE__) (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE) + +/** @brief Enable the specified TIM interrupt. + * @param __HANDLE__ specifies the TIM Handle. + * @param __INTERRUPT__ specifies the TIM interrupt source to enable. + * This parameter can be one of the following values: + * @arg TIM_IT_UPDATE: Update interrupt + * @arg TIM_IT_CC1: Capture/Compare 1 interrupt + * @arg TIM_IT_CC2: Capture/Compare 2 interrupt + * @arg TIM_IT_CC3: Capture/Compare 3 interrupt + * @arg TIM_IT_CC4: Capture/Compare 4 interrupt + * @arg TIM_IT_COM: Commutation interrupt + * @arg TIM_IT_TRIGGER: Trigger interrupt + * @arg TIM_IT_BREAK: Break interrupt + * @retval None + */ +#define __HAL_TIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER |= (__INTERRUPT__)) + +/** @brief Disable the specified TIM interrupt. + * @param __HANDLE__ specifies the TIM Handle. + * @param __INTERRUPT__ specifies the TIM interrupt source to disable. + * This parameter can be one of the following values: + * @arg TIM_IT_UPDATE: Update interrupt + * @arg TIM_IT_CC1: Capture/Compare 1 interrupt + * @arg TIM_IT_CC2: Capture/Compare 2 interrupt + * @arg TIM_IT_CC3: Capture/Compare 3 interrupt + * @arg TIM_IT_CC4: Capture/Compare 4 interrupt + * @arg TIM_IT_COM: Commutation interrupt + * @arg TIM_IT_TRIGGER: Trigger interrupt + * @arg TIM_IT_BREAK: Break interrupt + * @retval None + */ +#define __HAL_TIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER &= ~(__INTERRUPT__)) + +/** @brief Enable the specified DMA request. + * @param __HANDLE__ specifies the TIM Handle. + * @param __DMA__ specifies the TIM DMA request to enable. + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: Update DMA request + * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request + * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request + * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request + * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request + * @arg TIM_DMA_COM: Commutation DMA request + * @arg TIM_DMA_TRIGGER: Trigger DMA request + * @retval None + */ +#define __HAL_TIM_ENABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER |= (__DMA__)) + +/** @brief Disable the specified DMA request. + * @param __HANDLE__ specifies the TIM Handle. + * @param __DMA__ specifies the TIM DMA request to disable. + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: Update DMA request + * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request + * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request + * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request + * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request + * @arg TIM_DMA_COM: Commutation DMA request + * @arg TIM_DMA_TRIGGER: Trigger DMA request + * @retval None + */ +#define __HAL_TIM_DISABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER &= ~(__DMA__)) + +/** @brief Check whether the specified TIM interrupt flag is set or not. + * @param __HANDLE__ specifies the TIM Handle. + * @param __FLAG__ specifies the TIM interrupt flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_UPDATE: Update interrupt flag + * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag + * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag + * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag + * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag + * @arg TIM_FLAG_COM: Commutation interrupt flag + * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag + * @arg TIM_FLAG_BREAK: Break interrupt flag + * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag + * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag + * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag + * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_TIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR &(__FLAG__)) == (__FLAG__)) + +/** @brief Clear the specified TIM interrupt flag. + * @param __HANDLE__ specifies the TIM Handle. + * @param __FLAG__ specifies the TIM interrupt flag to clear. + * This parameter can be one of the following values: + * @arg TIM_FLAG_UPDATE: Update interrupt flag + * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag + * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag + * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag + * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag + * @arg TIM_FLAG_COM: Commutation interrupt flag + * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag + * @arg TIM_FLAG_BREAK: Break interrupt flag + * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag + * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag + * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag + * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_TIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) + +/** + * @brief Check whether the specified TIM interrupt source is enabled or not. + * @param __HANDLE__ TIM handle + * @param __INTERRUPT__ specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_UPDATE: Update interrupt + * @arg TIM_IT_CC1: Capture/Compare 1 interrupt + * @arg TIM_IT_CC2: Capture/Compare 2 interrupt + * @arg TIM_IT_CC3: Capture/Compare 3 interrupt + * @arg TIM_IT_CC4: Capture/Compare 4 interrupt + * @arg TIM_IT_COM: Commutation interrupt + * @arg TIM_IT_TRIGGER: Trigger interrupt + * @arg TIM_IT_BREAK: Break interrupt + * @retval The state of TIM_IT (SET or RESET). + */ +#define __HAL_TIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->DIER & (__INTERRUPT__)) \ + == (__INTERRUPT__)) ? SET : RESET) + +/** @brief Clear the TIM interrupt pending bits. + * @param __HANDLE__ TIM handle + * @param __INTERRUPT__ specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg TIM_IT_UPDATE: Update interrupt + * @arg TIM_IT_CC1: Capture/Compare 1 interrupt + * @arg TIM_IT_CC2: Capture/Compare 2 interrupt + * @arg TIM_IT_CC3: Capture/Compare 3 interrupt + * @arg TIM_IT_CC4: Capture/Compare 4 interrupt + * @arg TIM_IT_COM: Commutation interrupt + * @arg TIM_IT_TRIGGER: Trigger interrupt + * @arg TIM_IT_BREAK: Break interrupt + * @retval None + */ +#define __HAL_TIM_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->SR = ~(__INTERRUPT__)) + +/** + * @brief Indicates whether or not the TIM Counter is used as downcounter. + * @param __HANDLE__ TIM handle. + * @retval False (Counter used as upcounter) or True (Counter used as downcounter) + * @note This macro is particularly useful to get the counting mode when the timer operates in Center-aligned mode + * or Encoder mode. + */ +#define __HAL_TIM_IS_TIM_COUNTING_DOWN(__HANDLE__) (((__HANDLE__)->Instance->CR1 &(TIM_CR1_DIR)) == (TIM_CR1_DIR)) + +/** + * @brief Set the TIM Prescaler on runtime. + * @param __HANDLE__ TIM handle. + * @param __PRESC__ specifies the Prescaler new value. + * @retval None + */ +#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__) ((__HANDLE__)->Instance->PSC = (__PRESC__)) + +/** + * @brief Set the TIM Counter Register value on runtime. + * @param __HANDLE__ TIM handle. + * @param __COUNTER__ specifies the Counter register new value. + * @retval None + */ +#define __HAL_TIM_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNT = (__COUNTER__)) + +/** + * @brief Get the TIM Counter Register value on runtime. + * @param __HANDLE__ TIM handle. + * @retval 16-bit or 32-bit value of the timer counter register (TIMx_CNT) + */ +#define __HAL_TIM_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNT) + +/** + * @brief Set the TIM Autoreload Register value on runtime without calling another time any Init function. + * @param __HANDLE__ TIM handle. + * @param __AUTORELOAD__ specifies the Counter register new value. + * @retval None + */ +#define __HAL_TIM_SET_AUTORELOAD(__HANDLE__, __AUTORELOAD__) \ + do{ \ + (__HANDLE__)->Instance->ARR = (__AUTORELOAD__); \ + (__HANDLE__)->Init.Period = (__AUTORELOAD__); \ + } while(0) + +/** + * @brief Get the TIM Autoreload Register value on runtime. + * @param __HANDLE__ TIM handle. + * @retval 16-bit or 32-bit value of the timer auto-reload register(TIMx_ARR) + */ +#define __HAL_TIM_GET_AUTORELOAD(__HANDLE__) ((__HANDLE__)->Instance->ARR) + +/** + * @brief Set the TIM Clock Division value on runtime without calling another time any Init function. + * @param __HANDLE__ TIM handle. + * @param __CKD__ specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT + * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT + * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT + * @retval None + */ +#define __HAL_TIM_SET_CLOCKDIVISION(__HANDLE__, __CKD__) \ + do{ \ + (__HANDLE__)->Instance->CR1 &= (~TIM_CR1_CKD); \ + (__HANDLE__)->Instance->CR1 |= (__CKD__); \ + (__HANDLE__)->Init.ClockDivision = (__CKD__); \ + } while(0) + +/** + * @brief Get the TIM Clock Division value on runtime. + * @param __HANDLE__ TIM handle. + * @retval The clock division can be one of the following values: + * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT + * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT + * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT + */ +#define __HAL_TIM_GET_CLOCKDIVISION(__HANDLE__) ((__HANDLE__)->Instance->CR1 & TIM_CR1_CKD) + +/** + * @brief Set the TIM Input Capture prescaler on runtime without calling another time HAL_TIM_IC_ConfigChannel() + * function. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param __ICPSC__ specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +#define __HAL_TIM_SET_ICPRESCALER(__HANDLE__, __CHANNEL__, __ICPSC__) \ + do{ \ + TIM_RESET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__)); \ + TIM_SET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__), (__ICPSC__)); \ + } while(0) + +/** + * @brief Get the TIM Input Capture prescaler on runtime. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: get input capture 1 prescaler value + * @arg TIM_CHANNEL_2: get input capture 2 prescaler value + * @arg TIM_CHANNEL_3: get input capture 3 prescaler value + * @arg TIM_CHANNEL_4: get input capture 4 prescaler value + * @retval The input capture prescaler can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + */ +#define __HAL_TIM_GET_ICPRESCALER(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC1PSC) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? (((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC2PSC) >> 8U) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC3PSC) :\ + (((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC4PSC)) >> 8U) + +/** + * @brief Set the TIM Capture Compare Register value on runtime without calling another time ConfigChannel function. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param __COMPARE__ specifies the Capture Compare register new value. + * @retval None + */ +#define __HAL_TIM_SET_COMPARE(__HANDLE__, __CHANNEL__, __COMPARE__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1 = (__COMPARE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2 = (__COMPARE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3 = (__COMPARE__)) :\ + ((__HANDLE__)->Instance->CCR4 = (__COMPARE__))) + +/** + * @brief Get the TIM Capture Compare Register value on runtime. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channel associated with the capture compare register + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: get capture/compare 1 register value + * @arg TIM_CHANNEL_2: get capture/compare 2 register value + * @arg TIM_CHANNEL_3: get capture/compare 3 register value + * @arg TIM_CHANNEL_4: get capture/compare 4 register value + * @retval 16-bit or 32-bit value of the capture/compare register (TIMx_CCRy) + */ +#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3) :\ + ((__HANDLE__)->Instance->CCR4)) + +/** + * @brief Set the TIM Output compare preload. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval None + */ +#define __HAL_TIM_ENABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1PE) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2PE) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3PE) :\ + ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4PE)) + +/** + * @brief Reset the TIM Output compare preload. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval None + */ +#define __HAL_TIM_DISABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1PE) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2PE) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3PE) :\ + ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4PE)) + +/** + * @brief Enable fast mode for a given channel. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @note When fast mode is enabled an active edge on the trigger input acts + * like a compare match on CCx output. Delay to sample the trigger + * input and to activate CCx output is reduced to 3 clock cycles. + * @note Fast mode acts only if the channel is configured in PWM1 or PWM2 mode. + * @retval None + */ +#define __HAL_TIM_ENABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1FE) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2FE) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3FE) :\ + ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4FE)) + +/** + * @brief Disable fast mode for a given channel. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @note When fast mode is disabled CCx output behaves normally depending + * on counter and CCRx values even when the trigger is ON. The minimum + * delay to activate CCx output when an active edge occurs on the + * trigger input is 5 clock cycles. + * @retval None + */ +#define __HAL_TIM_DISABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE) :\ + ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE)) + +/** + * @brief Set the Update Request Source (URS) bit of the TIMx_CR1 register. + * @param __HANDLE__ TIM handle. + * @note When the URS bit of the TIMx_CR1 register is set, only counter + * overflow/underflow generates an update interrupt or DMA request (if + * enabled) + * @retval None + */ +#define __HAL_TIM_URS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|= TIM_CR1_URS) + +/** + * @brief Reset the Update Request Source (URS) bit of the TIMx_CR1 register. + * @param __HANDLE__ TIM handle. + * @note When the URS bit of the TIMx_CR1 register is reset, any of the + * following events generate an update interrupt or DMA request (if + * enabled): + * _ Counter overflow underflow + * _ Setting the UG bit + * _ Update generation through the slave mode controller + * @retval None + */ +#define __HAL_TIM_URS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1&=~TIM_CR1_URS) + +/** + * @brief Set the TIM Capture x input polarity on runtime. + * @param __HANDLE__ TIM handle. + * @param __CHANNEL__ TIM Channels to be configured. + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param __POLARITY__ Polarity for TIx source + * @arg TIM_INPUTCHANNELPOLARITY_RISING: Rising Edge + * @arg TIM_INPUTCHANNELPOLARITY_FALLING: Falling Edge + * @arg TIM_INPUTCHANNELPOLARITY_BOTHEDGE: Rising and Falling Edge + * @retval None + */ +#define __HAL_TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ + do{ \ + TIM_RESET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__)); \ + TIM_SET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__), (__POLARITY__)); \ + }while(0) + +/** @brief Select the Capture/compare DMA request source. + * @param __HANDLE__ specifies the TIM Handle. + * @param __CCDMA__ specifies Capture/compare DMA request source + * This parameter can be one of the following values: + * @arg TIM_CCDMAREQUEST_CC: CCx DMA request generated on Capture/Compare event + * @arg TIM_CCDMAREQUEST_UPDATE: CCx DMA request generated on Update event + * @retval None + */ +#define __HAL_TIM_SELECT_CCDMAREQUEST(__HANDLE__, __CCDMA__) \ + MODIFY_REG((__HANDLE__)->Instance->CR2, TIM_CR2_CCDS, (__CCDMA__)) + +/** + * @} + */ +/* End of exported macros ----------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup TIM_Private_Constants TIM Private Constants + * @{ + */ +/* The counter of a timer instance is disabled only if all the CCx and CCxN + channels have been disabled */ +#define TIM_CCER_CCxE_MASK ((uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)) +#define TIM_CCER_CCxNE_MASK ((uint32_t)(TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) +/** + * @} + */ +/* End of private constants --------------------------------------------------*/ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup TIM_Private_Macros TIM Private Macros + * @{ + */ +#define IS_TIM_CLEARINPUT_SOURCE(__MODE__) (((__MODE__) == TIM_CLEARINPUTSOURCE_NONE) || \ + ((__MODE__) == TIM_CLEARINPUTSOURCE_ETR)) + +#define IS_TIM_DMA_BASE(__BASE__) (((__BASE__) == TIM_DMABASE_CR1) || \ + ((__BASE__) == TIM_DMABASE_CR2) || \ + ((__BASE__) == TIM_DMABASE_SMCR) || \ + ((__BASE__) == TIM_DMABASE_DIER) || \ + ((__BASE__) == TIM_DMABASE_SR) || \ + ((__BASE__) == TIM_DMABASE_EGR) || \ + ((__BASE__) == TIM_DMABASE_CCMR1) || \ + ((__BASE__) == TIM_DMABASE_CCMR2) || \ + ((__BASE__) == TIM_DMABASE_CCER) || \ + ((__BASE__) == TIM_DMABASE_CNT) || \ + ((__BASE__) == TIM_DMABASE_PSC) || \ + ((__BASE__) == TIM_DMABASE_ARR) || \ + ((__BASE__) == TIM_DMABASE_RCR) || \ + ((__BASE__) == TIM_DMABASE_CCR1) || \ + ((__BASE__) == TIM_DMABASE_CCR2) || \ + ((__BASE__) == TIM_DMABASE_CCR3) || \ + ((__BASE__) == TIM_DMABASE_CCR4) || \ + ((__BASE__) == TIM_DMABASE_BDTR)) + +#define IS_TIM_EVENT_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFFFF00U) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) + +#define IS_TIM_COUNTER_MODE(__MODE__) (((__MODE__) == TIM_COUNTERMODE_UP) || \ + ((__MODE__) == TIM_COUNTERMODE_DOWN) || \ + ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED1) || \ + ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED2) || \ + ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED3)) + +#define IS_TIM_CLOCKDIVISION_DIV(__DIV__) (((__DIV__) == TIM_CLOCKDIVISION_DIV1) || \ + ((__DIV__) == TIM_CLOCKDIVISION_DIV2) || \ + ((__DIV__) == TIM_CLOCKDIVISION_DIV4)) + +#define IS_TIM_AUTORELOAD_PRELOAD(PRELOAD) (((PRELOAD) == TIM_AUTORELOAD_PRELOAD_DISABLE) || \ + ((PRELOAD) == TIM_AUTORELOAD_PRELOAD_ENABLE)) + +#define IS_TIM_FAST_STATE(__STATE__) (((__STATE__) == TIM_OCFAST_DISABLE) || \ + ((__STATE__) == TIM_OCFAST_ENABLE)) + +#define IS_TIM_OC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCPOLARITY_HIGH) || \ + ((__POLARITY__) == TIM_OCPOLARITY_LOW)) + +#define IS_TIM_OCN_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCNPOLARITY_HIGH) || \ + ((__POLARITY__) == TIM_OCNPOLARITY_LOW)) + +#define IS_TIM_OCIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCIDLESTATE_SET) || \ + ((__STATE__) == TIM_OCIDLESTATE_RESET)) + +#define IS_TIM_OCNIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCNIDLESTATE_SET) || \ + ((__STATE__) == TIM_OCNIDLESTATE_RESET)) + +#define IS_TIM_ENCODERINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_RISING) || \ + ((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_FALLING)) + +#define IS_TIM_IC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ICPOLARITY_RISING) || \ + ((__POLARITY__) == TIM_ICPOLARITY_FALLING) || \ + ((__POLARITY__) == TIM_ICPOLARITY_BOTHEDGE)) + +#define IS_TIM_IC_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_ICSELECTION_DIRECTTI) || \ + ((__SELECTION__) == TIM_ICSELECTION_INDIRECTTI) || \ + ((__SELECTION__) == TIM_ICSELECTION_TRC)) + +#define IS_TIM_IC_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_ICPSC_DIV1) || \ + ((__PRESCALER__) == TIM_ICPSC_DIV2) || \ + ((__PRESCALER__) == TIM_ICPSC_DIV4) || \ + ((__PRESCALER__) == TIM_ICPSC_DIV8)) + +#define IS_TIM_OPM_MODE(__MODE__) (((__MODE__) == TIM_OPMODE_SINGLE) || \ + ((__MODE__) == TIM_OPMODE_REPETITIVE)) + +#define IS_TIM_ENCODER_MODE(__MODE__) (((__MODE__) == TIM_ENCODERMODE_TI1) || \ + ((__MODE__) == TIM_ENCODERMODE_TI2) || \ + ((__MODE__) == TIM_ENCODERMODE_TI12)) + +#define IS_TIM_DMA_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFF80FFU) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) + +#define IS_TIM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ + ((__CHANNEL__) == TIM_CHANNEL_2) || \ + ((__CHANNEL__) == TIM_CHANNEL_3) || \ + ((__CHANNEL__) == TIM_CHANNEL_4) || \ + ((__CHANNEL__) == TIM_CHANNEL_ALL)) + +#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ + ((__CHANNEL__) == TIM_CHANNEL_2)) + +#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ + ((__CHANNEL__) == TIM_CHANNEL_2) || \ + ((__CHANNEL__) == TIM_CHANNEL_3)) + +#define IS_TIM_CLOCKSOURCE(__CLOCK__) (((__CLOCK__) == TIM_CLOCKSOURCE_INTERNAL) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE1) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE2) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_TI1ED) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_TI1) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_TI2) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ITR0) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ITR1) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ITR2) || \ + ((__CLOCK__) == TIM_CLOCKSOURCE_ITR3)) + +#define IS_TIM_CLOCKPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLOCKPOLARITY_INVERTED) || \ + ((__POLARITY__) == TIM_CLOCKPOLARITY_NONINVERTED) || \ + ((__POLARITY__) == TIM_CLOCKPOLARITY_RISING) || \ + ((__POLARITY__) == TIM_CLOCKPOLARITY_FALLING) || \ + ((__POLARITY__) == TIM_CLOCKPOLARITY_BOTHEDGE)) + +#define IS_TIM_CLOCKPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV1) || \ + ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV2) || \ + ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV4) || \ + ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV8)) + +#define IS_TIM_CLOCKFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) + +#define IS_TIM_CLEARINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLEARINPUTPOLARITY_INVERTED) || \ + ((__POLARITY__) == TIM_CLEARINPUTPOLARITY_NONINVERTED)) + +#define IS_TIM_CLEARINPUT_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV1) || \ + ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV2) || \ + ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV4) || \ + ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV8)) + +#define IS_TIM_CLEARINPUT_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) + +#define IS_TIM_OSSR_STATE(__STATE__) (((__STATE__) == TIM_OSSR_ENABLE) || \ + ((__STATE__) == TIM_OSSR_DISABLE)) + +#define IS_TIM_OSSI_STATE(__STATE__) (((__STATE__) == TIM_OSSI_ENABLE) || \ + ((__STATE__) == TIM_OSSI_DISABLE)) + +#define IS_TIM_LOCK_LEVEL(__LEVEL__) (((__LEVEL__) == TIM_LOCKLEVEL_OFF) || \ + ((__LEVEL__) == TIM_LOCKLEVEL_1) || \ + ((__LEVEL__) == TIM_LOCKLEVEL_2) || \ + ((__LEVEL__) == TIM_LOCKLEVEL_3)) + +#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL) + + +#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \ + ((__STATE__) == TIM_BREAK_DISABLE)) + +#define IS_TIM_BREAK_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_BREAKPOLARITY_LOW) || \ + ((__POLARITY__) == TIM_BREAKPOLARITY_HIGH)) + +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(__STATE__) (((__STATE__) == TIM_AUTOMATICOUTPUT_ENABLE) || \ + ((__STATE__) == TIM_AUTOMATICOUTPUT_DISABLE)) + +#define IS_TIM_TRGO_SOURCE(__SOURCE__) (((__SOURCE__) == TIM_TRGO_RESET) || \ + ((__SOURCE__) == TIM_TRGO_ENABLE) || \ + ((__SOURCE__) == TIM_TRGO_UPDATE) || \ + ((__SOURCE__) == TIM_TRGO_OC1) || \ + ((__SOURCE__) == TIM_TRGO_OC1REF) || \ + ((__SOURCE__) == TIM_TRGO_OC2REF) || \ + ((__SOURCE__) == TIM_TRGO_OC3REF) || \ + ((__SOURCE__) == TIM_TRGO_OC4REF)) + +#define IS_TIM_MSM_STATE(__STATE__) (((__STATE__) == TIM_MASTERSLAVEMODE_ENABLE) || \ + ((__STATE__) == TIM_MASTERSLAVEMODE_DISABLE)) + +#define IS_TIM_SLAVE_MODE(__MODE__) (((__MODE__) == TIM_SLAVEMODE_DISABLE) || \ + ((__MODE__) == TIM_SLAVEMODE_RESET) || \ + ((__MODE__) == TIM_SLAVEMODE_GATED) || \ + ((__MODE__) == TIM_SLAVEMODE_TRIGGER) || \ + ((__MODE__) == TIM_SLAVEMODE_EXTERNAL1)) + +#define IS_TIM_PWM_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_PWM1) || \ + ((__MODE__) == TIM_OCMODE_PWM2)) + +#define IS_TIM_OC_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_TIMING) || \ + ((__MODE__) == TIM_OCMODE_ACTIVE) || \ + ((__MODE__) == TIM_OCMODE_INACTIVE) || \ + ((__MODE__) == TIM_OCMODE_TOGGLE) || \ + ((__MODE__) == TIM_OCMODE_FORCED_ACTIVE) || \ + ((__MODE__) == TIM_OCMODE_FORCED_INACTIVE)) + +#define IS_TIM_TRIGGER_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ + ((__SELECTION__) == TIM_TS_ITR1) || \ + ((__SELECTION__) == TIM_TS_ITR2) || \ + ((__SELECTION__) == TIM_TS_ITR3) || \ + ((__SELECTION__) == TIM_TS_TI1F_ED) || \ + ((__SELECTION__) == TIM_TS_TI1FP1) || \ + ((__SELECTION__) == TIM_TS_TI2FP2) || \ + ((__SELECTION__) == TIM_TS_ETRF)) + +#define IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ + ((__SELECTION__) == TIM_TS_ITR1) || \ + ((__SELECTION__) == TIM_TS_ITR2) || \ + ((__SELECTION__) == TIM_TS_ITR3) || \ + ((__SELECTION__) == TIM_TS_NONE)) + +#define IS_TIM_TRIGGERPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_TRIGGERPOLARITY_INVERTED ) || \ + ((__POLARITY__) == TIM_TRIGGERPOLARITY_NONINVERTED) || \ + ((__POLARITY__) == TIM_TRIGGERPOLARITY_RISING ) || \ + ((__POLARITY__) == TIM_TRIGGERPOLARITY_FALLING ) || \ + ((__POLARITY__) == TIM_TRIGGERPOLARITY_BOTHEDGE )) + +#define IS_TIM_TRIGGERPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV1) || \ + ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV2) || \ + ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV4) || \ + ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV8)) + +#define IS_TIM_TRIGGERFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) + +#define IS_TIM_TI1SELECTION(__TI1SELECTION__) (((__TI1SELECTION__) == TIM_TI1SELECTION_CH1) || \ + ((__TI1SELECTION__) == TIM_TI1SELECTION_XORCOMBINATION)) + +#define IS_TIM_DMA_LENGTH(__LENGTH__) (((__LENGTH__) == TIM_DMABURSTLENGTH_1TRANSFER) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_2TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_3TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_4TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_5TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_6TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_7TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_8TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_9TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_10TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_11TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_12TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_13TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_14TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_15TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_16TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_17TRANSFERS) || \ + ((__LENGTH__) == TIM_DMABURSTLENGTH_18TRANSFERS)) + +#define IS_TIM_DMA_DATA_LENGTH(LENGTH) (((LENGTH) >= 0x1U) && ((LENGTH) < 0x10000U)) + +#define IS_TIM_IC_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) + +#define IS_TIM_DEADTIME(__DEADTIME__) ((__DEADTIME__) <= 0xFFU) + +#define IS_TIM_SLAVEMODE_TRIGGER_ENABLED(__TRIGGER__) ((__TRIGGER__) == TIM_SLAVEMODE_TRIGGER) + +#define TIM_SET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__, __ICPSC__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= (__ICPSC__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= ((__ICPSC__) << 8U)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= (__ICPSC__)) :\ + ((__HANDLE__)->Instance->CCMR2 |= ((__ICPSC__) << 8U))) + +#define TIM_RESET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC) :\ + ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC)) + +#define TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER |= (__POLARITY__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 4U)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 8U)) :\ + ((__HANDLE__)->Instance->CCER |= (((__POLARITY__) << 12U)))) + +#define TIM_RESET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP)) :\ + ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP))) + +#define TIM_CHANNEL_STATE_GET(__HANDLE__, __CHANNEL__)\ + (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelState[0] :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelState[1] :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelState[2] :\ + (__HANDLE__)->ChannelState[3]) + +#define TIM_CHANNEL_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__)) :\ + ((__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__))) + +#define TIM_CHANNEL_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ + (__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__); \ + } while(0) + +#define TIM_CHANNEL_N_STATE_GET(__HANDLE__, __CHANNEL__)\ + (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelNState[0] :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelNState[1] :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelNState[2] :\ + (__HANDLE__)->ChannelNState[3]) + +#define TIM_CHANNEL_N_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ + (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelNState[0] = (__CHANNEL_STATE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelNState[1] = (__CHANNEL_STATE__)) :\ + ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelNState[2] = (__CHANNEL_STATE__)) :\ + ((__HANDLE__)->ChannelNState[3] = (__CHANNEL_STATE__))) + +#define TIM_CHANNEL_N_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ + (__HANDLE__)->ChannelNState[0] = \ + (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelNState[1] = \ + (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelNState[2] = \ + (__CHANNEL_STATE__); \ + (__HANDLE__)->ChannelNState[3] = \ + (__CHANNEL_STATE__); \ + } while(0) + +/** + * @} + */ +/* End of private macros -----------------------------------------------------*/ + +/* Include TIM HAL Extended module */ +#include "stm32f4xx_hal_tim_ex.h" + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup TIM_Exported_Functions TIM Exported Functions + * @{ + */ + +/** @addtogroup TIM_Exported_Functions_Group1 TIM Time Base functions + * @brief Time Base functions + * @{ + */ +/* Time Base functions ********************************************************/ +HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group2 TIM Output Compare functions + * @brief TIM Output Compare functions + * @{ + */ +/* Timer Output Compare functions *********************************************/ +HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group3 TIM PWM functions + * @brief TIM PWM functions + * @{ + */ +/* Timer PWM functions ********************************************************/ +HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group4 TIM Input Capture functions + * @brief TIM Input Capture functions + * @{ + */ +/* Timer Input Capture functions **********************************************/ +HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group5 TIM One Pulse functions + * @brief TIM One Pulse functions + * @{ + */ +/* Timer One Pulse functions **************************************************/ +HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode); +HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group6 TIM Encoder functions + * @brief TIM Encoder functions + * @{ + */ +/* Timer Encoder functions ****************************************************/ +HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig); +HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim); +void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim); +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, + uint32_t *pData2, uint16_t Length); +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIM_Exported_Functions_Group7 TIM IRQ handler management + * @brief IRQ handler management + * @{ + */ +/* Interrupt Handler functions ***********************************************/ +void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim); +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions + * @brief Peripheral Control functions + * @{ + */ +/* Control functions *********************************************************/ +HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, + uint32_t OutputChannel, uint32_t InputChannel); +HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, TIM_ClearInputConfigTypeDef *sClearInputConfig, + uint32_t Channel); +HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig); +HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection); +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength); +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength); +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); +HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource); +uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions + * @brief TIM Callbacks functions + * @{ + */ +/* Callback in non blocking modes (Interrupt and DMA) *************************/ +void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim); +void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim); + +/* Callbacks Register/UnRegister functions ***********************************/ +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, + pTIM_CallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions + * @brief Peripheral State functions + * @{ + */ +/* Peripheral State functions ************************************************/ +HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim); + +/* Peripheral Channel state functions ************************************************/ +HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim); +HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim); +/** + * @} + */ + +/** + * @} + */ +/* End of exported functions -------------------------------------------------*/ + +/* Private functions----------------------------------------------------------*/ +/** @defgroup TIM_Private_Functions TIM Private Functions + * @{ + */ +void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure); +void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, uint32_t TIM_ICFilter); +void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, + uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter); + +void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma); +void TIM_DMAError(DMA_HandleTypeDef *hdma); +void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma); +void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma); +void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +void TIM_ResetCallback(TIM_HandleTypeDef *htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ +/* End of private functions --------------------------------------------------*/ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_HAL_TIM_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h index 39fb500..a43611b 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h @@ -1,354 +1,354 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim_ex.h - * @author MCD Application Team - * @brief Header file of TIM HAL Extended module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_EX_H -#define STM32F4xx_HAL_TIM_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIMEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Types TIM Extended Exported Types - * @{ - */ - -/** - * @brief TIM Hall sensor Configuration Structure definition - */ - -typedef struct -{ - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ -} TIM_HallSensor_InitTypeDef; -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants - * @{ - */ - -/** @defgroup TIMEx_Remap TIM Extended Remapping - * @{ - */ -#if defined (TIM2) -#if defined(TIM8) -#define TIM_TIM2_TIM8_TRGO 0x00000000U /*!< TIM2 ITR1 is connected to TIM8 TRGO */ -#else -#define TIM_TIM2_ETH_PTP TIM_OR_ITR1_RMP_0 /*!< TIM2 ITR1 is connected to PTP trigger output */ -#endif /* TIM8 */ -#define TIM_TIM2_USBFS_SOF TIM_OR_ITR1_RMP_1 /*!< TIM2 ITR1 is connected to OTG FS SOF */ -#define TIM_TIM2_USBHS_SOF (TIM_OR_ITR1_RMP_1 | TIM_OR_ITR1_RMP_0) /*!< TIM2 ITR1 is connected to OTG HS SOF */ -#endif /* TIM2 */ - -#define TIM_TIM5_GPIO 0x00000000U /*!< TIM5 TI4 is connected to GPIO */ -#define TIM_TIM5_LSI TIM_OR_TI4_RMP_0 /*!< TIM5 TI4 is connected to LSI */ -#define TIM_TIM5_LSE TIM_OR_TI4_RMP_1 /*!< TIM5 TI4 is connected to LSE */ -#define TIM_TIM5_RTC (TIM_OR_TI4_RMP_1 | TIM_OR_TI4_RMP_0) /*!< TIM5 TI4 is connected to the RTC wakeup interrupt */ - -#define TIM_TIM11_GPIO 0x00000000U /*!< TIM11 TI1 is connected to GPIO */ -#define TIM_TIM11_HSE TIM_OR_TI1_RMP_1 /*!< TIM11 TI1 is connected to HSE_RTC clock */ -#if defined(SPDIFRX) -#define TIM_TIM11_SPDIFRX TIM_OR_TI1_RMP_0 /*!< TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC */ -#endif /* SPDIFRX*/ - -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define LPTIM_REMAP_MASK 0x10000000U - -#define TIM_TIM9_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM9 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM9_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM9_ITR1_RMP) /*!< TIM9 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM5_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM5 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM5_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM5_ITR1_RMP) /*!< TIM5 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM1_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM1 ITR2 is connected to TIM3 TRGO */ -#define TIM_TIM1_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM1_ITR2_RMP) /*!< TIM1 ITR2 is connected to LPTIM1 output */ -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros - * @{ - */ - -/** - * @} - */ -/* End of exported macro -----------------------------------------------------*/ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup TIMEx_Private_Macros TIM Extended Private Macros - * @{ - */ -#if defined(SPDIFRX) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_SPDIFRX) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#elif defined(TIM2) -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE))) || \ - (((INSTANCE) == TIM1) && (((TIM_REMAP) == TIM_TIM1_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM1_LPTIM))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM5_LPTIM))) || \ - (((INSTANCE) == TIM9) && (((TIM_REMAP) == TIM_TIM9_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM9_LPTIM)))) -#elif defined(TIM8) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_ETH_PTP) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* SPDIFRX */ - -/** - * @} - */ -/* End of private macro ------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions - * @{ - */ - -/** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions - * @brief Timer Hall Sensor functions - * @{ - */ -/* Timer Hall Sensor functions **********************************************/ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim); - -void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim); - -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions - * @brief Timer Complementary Output Compare functions - * @{ - */ -/* Timer Complementary Output Compare functions *****************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions - * @brief Timer Complementary PWM functions - * @{ - */ -/* Timer Complementary PWM functions ****************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions - * @brief Timer Complementary One Pulse functions - * @{ - */ -/* Timer Complementary One Pulse functions **********************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Extended Control functions ************************************************/ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, - TIM_MasterConfigTypeDef *sMasterConfig); -HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, - TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig); -HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions - * @brief Extended Callbacks functions - * @{ - */ -/* Extended Callback **********************************************************/ -void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions - * @brief Extended Peripheral State functions - * @{ - */ -/* Extended Peripheral State functions ***************************************/ -HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @addtogroup TIMEx_Private_Functions TIM Extended Private Functions - * @{ - */ -void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma); -void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_TIM_EX_H */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim_ex.h + * @author MCD Application Team + * @brief Header file of TIM HAL Extended module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_HAL_TIM_EX_H +#define STM32F4xx_HAL_TIM_EX_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup TIMEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup TIMEx_Exported_Types TIM Extended Exported Types + * @{ + */ + +/** + * @brief TIM Hall sensor Configuration Structure definition + */ + +typedef struct +{ + uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint32_t IC1Filter; /*!< Specifies the input capture filter. + This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ + + uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ +} TIM_HallSensor_InitTypeDef; +/** + * @} + */ +/* End of exported types -----------------------------------------------------*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants + * @{ + */ + +/** @defgroup TIMEx_Remap TIM Extended Remapping + * @{ + */ +#if defined (TIM2) +#if defined(TIM8) +#define TIM_TIM2_TIM8_TRGO 0x00000000U /*!< TIM2 ITR1 is connected to TIM8 TRGO */ +#else +#define TIM_TIM2_ETH_PTP TIM_OR_ITR1_RMP_0 /*!< TIM2 ITR1 is connected to PTP trigger output */ +#endif /* TIM8 */ +#define TIM_TIM2_USBFS_SOF TIM_OR_ITR1_RMP_1 /*!< TIM2 ITR1 is connected to OTG FS SOF */ +#define TIM_TIM2_USBHS_SOF (TIM_OR_ITR1_RMP_1 | TIM_OR_ITR1_RMP_0) /*!< TIM2 ITR1 is connected to OTG HS SOF */ +#endif /* TIM2 */ + +#define TIM_TIM5_GPIO 0x00000000U /*!< TIM5 TI4 is connected to GPIO */ +#define TIM_TIM5_LSI TIM_OR_TI4_RMP_0 /*!< TIM5 TI4 is connected to LSI */ +#define TIM_TIM5_LSE TIM_OR_TI4_RMP_1 /*!< TIM5 TI4 is connected to LSE */ +#define TIM_TIM5_RTC (TIM_OR_TI4_RMP_1 | TIM_OR_TI4_RMP_0) /*!< TIM5 TI4 is connected to the RTC wakeup interrupt */ + +#define TIM_TIM11_GPIO 0x00000000U /*!< TIM11 TI1 is connected to GPIO */ +#define TIM_TIM11_HSE TIM_OR_TI1_RMP_1 /*!< TIM11 TI1 is connected to HSE_RTC clock */ +#if defined(SPDIFRX) +#define TIM_TIM11_SPDIFRX TIM_OR_TI1_RMP_0 /*!< TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC */ +#endif /* SPDIFRX*/ + +#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) +#define LPTIM_REMAP_MASK 0x10000000U + +#define TIM_TIM9_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM9 ITR1 is connected to TIM3 TRGO */ +#define TIM_TIM9_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM9_ITR1_RMP) /*!< TIM9 ITR1 is connected to LPTIM1 output */ + +#define TIM_TIM5_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM5 ITR1 is connected to TIM3 TRGO */ +#define TIM_TIM5_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM5_ITR1_RMP) /*!< TIM5 ITR1 is connected to LPTIM1 output */ + +#define TIM_TIM1_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM1 ITR2 is connected to TIM3 TRGO */ +#define TIM_TIM1_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM1_ITR2_RMP) /*!< TIM1 ITR2 is connected to LPTIM1 output */ +#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ +/** + * @} + */ + +/** + * @} + */ +/* End of exported constants -------------------------------------------------*/ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros + * @{ + */ + +/** + * @} + */ +/* End of exported macro -----------------------------------------------------*/ + +/* Private macro -------------------------------------------------------------*/ +/** @defgroup TIMEx_Private_Macros TIM Extended Private Macros + * @{ + */ +#if defined(SPDIFRX) +#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ + ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ + ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ + ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ + (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ + ((TIM_REMAP) == TIM_TIM5_LSI) || \ + ((TIM_REMAP) == TIM_TIM5_LSE) || \ + ((TIM_REMAP) == TIM_TIM5_RTC))) || \ + (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ + ((TIM_REMAP) == TIM_TIM11_SPDIFRX) || \ + ((TIM_REMAP) == TIM_TIM11_HSE)))) +#elif defined(TIM2) +#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) +#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ + ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ + ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ + ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ + (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ + ((TIM_REMAP) == TIM_TIM5_LSI) || \ + ((TIM_REMAP) == TIM_TIM5_LSE) || \ + ((TIM_REMAP) == TIM_TIM5_RTC))) || \ + (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ + ((TIM_REMAP) == TIM_TIM11_HSE))) || \ + (((INSTANCE) == TIM1) && (((TIM_REMAP) == TIM_TIM1_TIM3_TRGO) || \ + ((TIM_REMAP) == TIM_TIM1_LPTIM))) || \ + (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_TIM3_TRGO) || \ + ((TIM_REMAP) == TIM_TIM5_LPTIM))) || \ + (((INSTANCE) == TIM9) && (((TIM_REMAP) == TIM_TIM9_TIM3_TRGO) || \ + ((TIM_REMAP) == TIM_TIM9_LPTIM)))) +#elif defined(TIM8) +#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ + ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ + ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ + ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ + (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ + ((TIM_REMAP) == TIM_TIM5_LSI) || \ + ((TIM_REMAP) == TIM_TIM5_LSE) || \ + ((TIM_REMAP) == TIM_TIM5_RTC))) || \ + (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ + ((TIM_REMAP) == TIM_TIM11_HSE)))) +#else +#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ + ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_ETH_PTP) || \ + ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ + ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ + (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ + ((TIM_REMAP) == TIM_TIM5_LSI) || \ + ((TIM_REMAP) == TIM_TIM5_LSE) || \ + ((TIM_REMAP) == TIM_TIM5_RTC))) || \ + (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ + ((TIM_REMAP) == TIM_TIM11_HSE)))) +#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ +#else +#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ + ((((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ + ((TIM_REMAP) == TIM_TIM5_LSI) || \ + ((TIM_REMAP) == TIM_TIM5_LSE) || \ + ((TIM_REMAP) == TIM_TIM5_RTC))) || \ + (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ + ((TIM_REMAP) == TIM_TIM11_HSE)))) +#endif /* SPDIFRX */ + +/** + * @} + */ +/* End of private macro ------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions + * @{ + */ + +/** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions + * @brief Timer Hall Sensor functions + * @{ + */ +/* Timer Hall Sensor functions **********************************************/ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig); +HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim); + +void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim); +void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim); + +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim); +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim); +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions + * @brief Timer Complementary Output Compare functions + * @{ + */ +/* Timer Complementary Output Compare functions *****************************/ +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); + +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); + +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions + * @brief Timer Complementary PWM functions + * @{ + */ +/* Timer Complementary PWM functions ****************************************/ +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); + +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); +/* Non-Blocking mode: DMA */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions + * @brief Timer Complementary One Pulse functions + * @{ + */ +/* Timer Complementary One Pulse functions **********************************/ +/* Blocking mode: Polling */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); + +/* Non-Blocking mode: Interrupt */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions + * @brief Peripheral Control functions + * @{ + */ +/* Extended Control functions ************************************************/ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource); +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource); +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource); +HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, + TIM_MasterConfigTypeDef *sMasterConfig); +HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, + TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig); +HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions + * @brief Extended Callbacks functions + * @{ + */ +/* Extended Callback **********************************************************/ +void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim); +void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim); +void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim); +/** + * @} + */ + +/** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions + * @brief Extended Peripheral State functions + * @{ + */ +/* Extended Peripheral State functions ***************************************/ +HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim); +HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN); +/** + * @} + */ + +/** + * @} + */ +/* End of exported functions -------------------------------------------------*/ + +/* Private functions----------------------------------------------------------*/ +/** @addtogroup TIMEx_Private_Functions TIM Extended Private Functions + * @{ + */ +void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma); +void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma); +/** + * @} + */ +/* End of private functions --------------------------------------------------*/ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + + +#endif /* STM32F4xx_HAL_TIM_EX_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h index c5f5d3e..543ebcc 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h @@ -1,884 +1,884 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_uart.h - * @author MCD Application Team - * @brief Header file of UART HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_UART_H -#define __STM32F4xx_HAL_UART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup UART - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Types UART Exported Types - * @{ - */ - -/** - * @brief UART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the UART communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (huart->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 - Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref UART_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref UART_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref UART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref UART_Mode */ - - uint32_t HwFlowCtl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref UART_Hardware_Flow_Control */ - - uint32_t OverSampling; /*!< Specifies whether the Over sampling 8 is enabled or disabled, to achieve higher speed (up to fPCLK/8). - This parameter can be a value of @ref UART_Over_Sampling */ -} UART_InitTypeDef; - -/** - * @brief HAL UART State structures definition - * @note HAL UART State value is a combination of 2 different substates: gState and RxState. - * - gState contains UART state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized. HAL UART Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_UART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_UART_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_UART_STATE_BUSY = 0x24U, /*!< an internal process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_UART_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_UART_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_UART_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -} HAL_UART_StateTypeDef; - -/** - * @brief HAL UART Reception type definition - * @note HAL UART Reception type value aims to identify which type of Reception is ongoing. - * It is expected to admit following values : - * HAL_UART_RECEPTION_STANDARD = 0x00U, - * HAL_UART_RECEPTION_TOIDLE = 0x01U, - */ -typedef uint32_t HAL_UART_RxTypeTypeDef; - -/** - * @brief UART handle Structure definition - */ -typedef struct __UART_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< UART registers base address */ - - UART_InitTypeDef Init; /*!< UART communication parameters */ - - const uint8_t *pTxBuffPtr; /*!< Pointer to UART Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< UART Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< UART Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to UART Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< UART Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< UART Rx Transfer Counter */ - - __IO HAL_UART_RxTypeTypeDef ReceptionType; /*!< Type of ongoing reception */ - - DMA_HandleTypeDef *hdmatx; /*!< UART Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< UART Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_UART_StateTypeDef gState; /*!< UART state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO HAL_UART_StateTypeDef RxState; /*!< UART state information related to Rx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< UART Error code */ - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Half Complete Callback */ - void (* TxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Complete Callback */ - void (* RxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Half Complete Callback */ - void (* RxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Complete Callback */ - void (* ErrorCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Error Callback */ - void (* AbortCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Complete Callback */ - void (* AbortTransmitCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Transmit Complete Callback */ - void (* AbortReceiveCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Receive Complete Callback */ - void (* WakeupCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Wakeup Callback */ - void (* RxEventCallback)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< UART Reception Event Callback */ - - void (* MspInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp Init callback */ - void (* MspDeInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp DeInit callback */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -} UART_HandleTypeDef; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -/** - * @brief HAL UART Callback ID enumeration definition - */ -typedef enum -{ - HAL_UART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< UART Tx Half Complete Callback ID */ - HAL_UART_TX_COMPLETE_CB_ID = 0x01U, /*!< UART Tx Complete Callback ID */ - HAL_UART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< UART Rx Half Complete Callback ID */ - HAL_UART_RX_COMPLETE_CB_ID = 0x03U, /*!< UART Rx Complete Callback ID */ - HAL_UART_ERROR_CB_ID = 0x04U, /*!< UART Error Callback ID */ - HAL_UART_ABORT_COMPLETE_CB_ID = 0x05U, /*!< UART Abort Complete Callback ID */ - HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< UART Abort Transmit Complete Callback ID */ - HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< UART Abort Receive Complete Callback ID */ - HAL_UART_WAKEUP_CB_ID = 0x08U, /*!< UART Wakeup Callback ID */ - - HAL_UART_MSPINIT_CB_ID = 0x0BU, /*!< UART MspInit callback ID */ - HAL_UART_MSPDEINIT_CB_ID = 0x0CU /*!< UART MspDeInit callback ID */ - -} HAL_UART_CallbackIDTypeDef; - -/** - * @brief HAL UART Callback pointer definition - */ -typedef void (*pUART_CallbackTypeDef)(UART_HandleTypeDef *huart); /*!< pointer to an UART callback function */ -typedef void (*pUART_RxEventCallbackTypeDef)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< pointer to a UART Rx Event specific callback function */ - -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UART_Exported_Constants UART Exported Constants - * @{ - */ - -/** @defgroup UART_Error_Code UART Error Code - * @{ - */ -#define HAL_UART_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_UART_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_UART_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_UART_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_UART_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_UART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define HAL_UART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup UART_Word_Length UART Word Length - * @{ - */ -#define UART_WORDLENGTH_8B 0x00000000U -#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup UART_Stop_Bits UART Number of Stop Bits - * @{ - */ -#define UART_STOPBITS_1 0x00000000U -#define UART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) -/** - * @} - */ - -/** @defgroup UART_Parity UART Parity - * @{ - */ -#define UART_PARITY_NONE 0x00000000U -#define UART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define UART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup UART_Hardware_Flow_Control UART Hardware Flow Control - * @{ - */ -#define UART_HWCONTROL_NONE 0x00000000U -#define UART_HWCONTROL_RTS ((uint32_t)USART_CR3_RTSE) -#define UART_HWCONTROL_CTS ((uint32_t)USART_CR3_CTSE) -#define UART_HWCONTROL_RTS_CTS ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) -/** - * @} - */ - -/** @defgroup UART_Mode UART Transfer Mode - * @{ - */ -#define UART_MODE_RX ((uint32_t)USART_CR1_RE) -#define UART_MODE_TX ((uint32_t)USART_CR1_TE) -#define UART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup UART_State UART State - * @{ - */ -#define UART_STATE_DISABLE 0x00000000U -#define UART_STATE_ENABLE ((uint32_t)USART_CR1_UE) -/** - * @} - */ - -/** @defgroup UART_Over_Sampling UART Over Sampling - * @{ - */ -#define UART_OVERSAMPLING_16 0x00000000U -#define UART_OVERSAMPLING_8 ((uint32_t)USART_CR1_OVER8) -/** - * @} - */ - -/** @defgroup UART_LIN_Break_Detection_Length UART LIN Break Detection Length - * @{ - */ -#define UART_LINBREAKDETECTLENGTH_10B 0x00000000U -#define UART_LINBREAKDETECTLENGTH_11B ((uint32_t)USART_CR2_LBDL) -/** - * @} - */ - -/** @defgroup UART_WakeUp_functions UART Wakeup Functions - * @{ - */ -#define UART_WAKEUPMETHOD_IDLELINE 0x00000000U -#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE) -/** - * @} - */ - -/** @defgroup UART_Flags UART FLags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define UART_FLAG_CTS ((uint32_t)USART_SR_CTS) -#define UART_FLAG_LBD ((uint32_t)USART_SR_LBD) -#define UART_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define UART_FLAG_TC ((uint32_t)USART_SR_TC) -#define UART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define UART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define UART_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define UART_FLAG_NE ((uint32_t)USART_SR_NE) -#define UART_FLAG_FE ((uint32_t)USART_SR_FE) -#define UART_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup UART_Interrupt_definition UART Interrupt Definitions - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask (16 bits) in the Y register - * - Y : Interrupt source register (2bits) - * - 0001: CR1 register - * - 0010: CR2 register - * - 0011: CR3 register - * @{ - */ - -#define UART_IT_PE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define UART_IT_TXE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define UART_IT_TC ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define UART_IT_RXNE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define UART_IT_IDLE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) - -#define UART_IT_LBD ((uint32_t)(UART_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) - -#define UART_IT_CTS ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) -#define UART_IT_ERR ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** @defgroup UART_RECEPTION_TYPE_Values UART Reception type values - * @{ - */ -#define HAL_UART_RECEPTION_STANDARD (0x00000000U) /*!< Standard reception */ -#define HAL_UART_RECEPTION_TOIDLE (0x00000001U) /*!< Reception till completion or IDLE event */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Macros UART Exported Macros - * @{ - */ - -/** @brief Reset UART handle gstate & RxState - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_UART_REGISTER_CALLBACKS */ - -/** @brief Flushes the UART DR register - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - */ -#define __HAL_UART_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Checks whether the specified UART flag is set or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) - * @arg UART_FLAG_LBD: LIN Break detection flag - * @arg UART_FLAG_TXE: Transmit data register empty flag - * @arg UART_FLAG_TC: Transmission Complete flag - * @arg UART_FLAG_RXNE: Receive data register not empty flag - * @arg UART_FLAG_IDLE: Idle Line detection flag - * @arg UART_FLAG_ORE: Overrun Error flag - * @arg UART_FLAG_NE: Noise Error flag - * @arg UART_FLAG_FE: Framing Error flag - * @arg UART_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the specified UART pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). - * @arg UART_FLAG_LBD: LIN Break detection flag. - * @arg UART_FLAG_TC: Transmission Complete flag. - * @arg UART_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * - * @retval None - */ -#define __HAL_UART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clears the UART PE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clears the UART FE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_FEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART NE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_NEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART ORE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_OREFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART IDLE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to enable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Disable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to disable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Checks whether the specified UART interrupt source is enabled or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __IT__ specifies the UART interrupt source to check. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_ERR: Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == UART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == UART_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & UART_IT_MASK)) - -/** @brief Enable CTS flow control - * @note This macro allows to enable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_CTSE; \ - } while(0U) - -/** @brief Disable CTS flow control - * @note This macro allows to disable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_CTSE); \ - } while(0U) - -/** @brief Enable RTS flow control - * This macro allows to enable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_RTSE; \ - } while(0U) - -/** @brief Disable RTS flow control - * This macro allows to disable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE);\ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_RTSE); \ - } while(0U) - -/** @brief Macro to enable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) - -/** @brief Macro to disable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ - &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup UART_Exported_Functions - * @{ - */ - -/** @addtogroup UART_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength); -HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod); -HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart); -void HAL_UART_MspInit(UART_HandleTypeDef *huart); -void HAL_UART_MspDeInit(UART_HandleTypeDef *huart); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, - pUART_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group2 IO operation functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart); - -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, - uint32_t Timeout); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart); - -void HAL_UART_IRQHandler(UART_HandleTypeDef *huart); -void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart); - -void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size); - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart); -uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UART_Private_Constants UART Private Constants - * @{ - */ -/** @brief UART interruptions flag mask - * - */ -#define UART_IT_MASK 0x0000FFFFU - -#define UART_CR1_REG_INDEX 1U -#define UART_CR2_REG_INDEX 2U -#define UART_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UART_Private_Macros UART Private Macros - * @{ - */ -#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B) || \ - ((LENGTH) == UART_WORDLENGTH_9B)) -#define IS_UART_LIN_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B)) -#define IS_UART_STOPBITS(STOPBITS) (((STOPBITS) == UART_STOPBITS_1) || \ - ((STOPBITS) == UART_STOPBITS_2)) -#define IS_UART_PARITY(PARITY) (((PARITY) == UART_PARITY_NONE) || \ - ((PARITY) == UART_PARITY_EVEN) || \ - ((PARITY) == UART_PARITY_ODD)) -#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\ - (((CONTROL) == UART_HWCONTROL_NONE) || \ - ((CONTROL) == UART_HWCONTROL_RTS) || \ - ((CONTROL) == UART_HWCONTROL_CTS) || \ - ((CONTROL) == UART_HWCONTROL_RTS_CTS)) -#define IS_UART_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00U)) -#define IS_UART_STATE(STATE) (((STATE) == UART_STATE_DISABLE) || \ - ((STATE) == UART_STATE_ENABLE)) -#define IS_UART_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16) || \ - ((SAMPLING) == UART_OVERSAMPLING_8)) -#define IS_UART_LIN_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16)) -#define IS_UART_LIN_BREAK_DETECT_LENGTH(LENGTH) (((LENGTH) == UART_LINBREAKDETECTLENGTH_10B) || \ - ((LENGTH) == UART_LINBREAKDETECTLENGTH_11B)) -#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \ - ((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK)) -#define IS_UART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 10500000U) -#define IS_UART_ADDRESS(ADDRESS) ((ADDRESS) <= 0x0FU) - -#define UART_DIV_SAMPLING16(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING16(_PCLK_, _BAUD_) (UART_DIV_SAMPLING16((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING16(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING16((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) * 100U)) * 16U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ -#define UART_BRR_SAMPLING16(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) << 4U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0xF0U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0x0FU)) - -#define UART_DIV_SAMPLING8(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING8(_PCLK_, _BAUD_) (UART_DIV_SAMPLING8((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING8(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING8((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) * 100U)) * 8U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ -#define UART_BRR_SAMPLING8(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) << 4U) + \ - ((UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0xF8U) << 1U) + \ - (UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0x07U)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup UART_Private_Functions UART Private Functions - * @{ - */ - -HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_UART_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_uart.h + * @author MCD Application Team + * @brief Header file of UART HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_UART_H +#define __STM32F4xx_HAL_UART_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup UART + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** @defgroup UART_Exported_Types UART Exported Types + * @{ + */ + +/** + * @brief UART Init Structure definition + */ +typedef struct +{ + uint32_t BaudRate; /*!< This member configures the UART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (huart->Init.BaudRate))) + - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 + Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ + + uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref UART_Word_Length */ + + uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref UART_Stop_Bits */ + + uint32_t Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref UART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref UART_Mode */ + + uint32_t HwFlowCtl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. + This parameter can be a value of @ref UART_Hardware_Flow_Control */ + + uint32_t OverSampling; /*!< Specifies whether the Over sampling 8 is enabled or disabled, to achieve higher speed (up to fPCLK/8). + This parameter can be a value of @ref UART_Over_Sampling */ +} UART_InitTypeDef; + +/** + * @brief HAL UART State structures definition + * @note HAL UART State value is a combination of 2 different substates: gState and RxState. + * - gState contains UART state information related to global Handle management + * and also information related to Tx operations. + * gState value coding follow below described bitmap : + * b7-b6 Error information + * 00 : No Error + * 01 : (Not Used) + * 10 : Timeout + * 11 : Error + * b5 Peripheral initialization status + * 0 : Reset (Peripheral not initialized) + * 1 : Init done (Peripheral initialized. HAL UART Init function already called) + * b4-b3 (not used) + * xx : Should be set to 00 + * b2 Intrinsic process state + * 0 : Ready + * 1 : Busy (Peripheral busy with some configuration or internal operations) + * b1 (not used) + * x : Should be set to 0 + * b0 Tx state + * 0 : Ready (no Tx operation ongoing) + * 1 : Busy (Tx operation ongoing) + * - RxState contains information related to Rx operations. + * RxState value coding follow below described bitmap : + * b7-b6 (not used) + * xx : Should be set to 00 + * b5 Peripheral initialization status + * 0 : Reset (Peripheral not initialized) + * 1 : Init done (Peripheral initialized) + * b4-b2 (not used) + * xxx : Should be set to 000 + * b1 Rx state + * 0 : Ready (no Rx operation ongoing) + * 1 : Busy (Rx operation ongoing) + * b0 (not used) + * x : Should be set to 0. + */ +typedef enum +{ + HAL_UART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized + Value is allowed for gState and RxState */ + HAL_UART_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use + Value is allowed for gState and RxState */ + HAL_UART_STATE_BUSY = 0x24U, /*!< an internal process is ongoing + Value is allowed for gState only */ + HAL_UART_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing + Value is allowed for gState only */ + HAL_UART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing + Value is allowed for RxState only */ + HAL_UART_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing + Not to be used for neither gState nor RxState. + Value is result of combination (Or) between gState and RxState values */ + HAL_UART_STATE_TIMEOUT = 0xA0U, /*!< Timeout state + Value is allowed for gState only */ + HAL_UART_STATE_ERROR = 0xE0U /*!< Error + Value is allowed for gState only */ +} HAL_UART_StateTypeDef; + +/** + * @brief HAL UART Reception type definition + * @note HAL UART Reception type value aims to identify which type of Reception is ongoing. + * It is expected to admit following values : + * HAL_UART_RECEPTION_STANDARD = 0x00U, + * HAL_UART_RECEPTION_TOIDLE = 0x01U, + */ +typedef uint32_t HAL_UART_RxTypeTypeDef; + +/** + * @brief UART handle Structure definition + */ +typedef struct __UART_HandleTypeDef +{ + USART_TypeDef *Instance; /*!< UART registers base address */ + + UART_InitTypeDef Init; /*!< UART communication parameters */ + + const uint8_t *pTxBuffPtr; /*!< Pointer to UART Tx transfer Buffer */ + + uint16_t TxXferSize; /*!< UART Tx Transfer size */ + + __IO uint16_t TxXferCount; /*!< UART Tx Transfer Counter */ + + uint8_t *pRxBuffPtr; /*!< Pointer to UART Rx transfer Buffer */ + + uint16_t RxXferSize; /*!< UART Rx Transfer size */ + + __IO uint16_t RxXferCount; /*!< UART Rx Transfer Counter */ + + __IO HAL_UART_RxTypeTypeDef ReceptionType; /*!< Type of ongoing reception */ + + DMA_HandleTypeDef *hdmatx; /*!< UART Tx DMA Handle parameters */ + + DMA_HandleTypeDef *hdmarx; /*!< UART Rx DMA Handle parameters */ + + HAL_LockTypeDef Lock; /*!< Locking object */ + + __IO HAL_UART_StateTypeDef gState; /*!< UART state information related to global Handle management + and also related to Tx operations. + This parameter can be a value of @ref HAL_UART_StateTypeDef */ + + __IO HAL_UART_StateTypeDef RxState; /*!< UART state information related to Rx operations. + This parameter can be a value of @ref HAL_UART_StateTypeDef */ + + __IO uint32_t ErrorCode; /*!< UART Error code */ + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + void (* TxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Half Complete Callback */ + void (* TxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Complete Callback */ + void (* RxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Half Complete Callback */ + void (* RxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Complete Callback */ + void (* ErrorCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Error Callback */ + void (* AbortCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Complete Callback */ + void (* AbortTransmitCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Transmit Complete Callback */ + void (* AbortReceiveCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Receive Complete Callback */ + void (* WakeupCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Wakeup Callback */ + void (* RxEventCallback)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< UART Reception Event Callback */ + + void (* MspInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp Init callback */ + void (* MspDeInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp DeInit callback */ +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +} UART_HandleTypeDef; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +/** + * @brief HAL UART Callback ID enumeration definition + */ +typedef enum +{ + HAL_UART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< UART Tx Half Complete Callback ID */ + HAL_UART_TX_COMPLETE_CB_ID = 0x01U, /*!< UART Tx Complete Callback ID */ + HAL_UART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< UART Rx Half Complete Callback ID */ + HAL_UART_RX_COMPLETE_CB_ID = 0x03U, /*!< UART Rx Complete Callback ID */ + HAL_UART_ERROR_CB_ID = 0x04U, /*!< UART Error Callback ID */ + HAL_UART_ABORT_COMPLETE_CB_ID = 0x05U, /*!< UART Abort Complete Callback ID */ + HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< UART Abort Transmit Complete Callback ID */ + HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< UART Abort Receive Complete Callback ID */ + HAL_UART_WAKEUP_CB_ID = 0x08U, /*!< UART Wakeup Callback ID */ + + HAL_UART_MSPINIT_CB_ID = 0x0BU, /*!< UART MspInit callback ID */ + HAL_UART_MSPDEINIT_CB_ID = 0x0CU /*!< UART MspDeInit callback ID */ + +} HAL_UART_CallbackIDTypeDef; + +/** + * @brief HAL UART Callback pointer definition + */ +typedef void (*pUART_CallbackTypeDef)(UART_HandleTypeDef *huart); /*!< pointer to an UART callback function */ +typedef void (*pUART_RxEventCallbackTypeDef)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< pointer to a UART Rx Event specific callback function */ + +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup UART_Exported_Constants UART Exported Constants + * @{ + */ + +/** @defgroup UART_Error_Code UART Error Code + * @{ + */ +#define HAL_UART_ERROR_NONE 0x00000000U /*!< No error */ +#define HAL_UART_ERROR_PE 0x00000001U /*!< Parity error */ +#define HAL_UART_ERROR_NE 0x00000002U /*!< Noise error */ +#define HAL_UART_ERROR_FE 0x00000004U /*!< Frame error */ +#define HAL_UART_ERROR_ORE 0x00000008U /*!< Overrun error */ +#define HAL_UART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +#define HAL_UART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup UART_Word_Length UART Word Length + * @{ + */ +#define UART_WORDLENGTH_8B 0x00000000U +#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) +/** + * @} + */ + +/** @defgroup UART_Stop_Bits UART Number of Stop Bits + * @{ + */ +#define UART_STOPBITS_1 0x00000000U +#define UART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) +/** + * @} + */ + +/** @defgroup UART_Parity UART Parity + * @{ + */ +#define UART_PARITY_NONE 0x00000000U +#define UART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) +#define UART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) +/** + * @} + */ + +/** @defgroup UART_Hardware_Flow_Control UART Hardware Flow Control + * @{ + */ +#define UART_HWCONTROL_NONE 0x00000000U +#define UART_HWCONTROL_RTS ((uint32_t)USART_CR3_RTSE) +#define UART_HWCONTROL_CTS ((uint32_t)USART_CR3_CTSE) +#define UART_HWCONTROL_RTS_CTS ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) +/** + * @} + */ + +/** @defgroup UART_Mode UART Transfer Mode + * @{ + */ +#define UART_MODE_RX ((uint32_t)USART_CR1_RE) +#define UART_MODE_TX ((uint32_t)USART_CR1_TE) +#define UART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) +/** + * @} + */ + +/** @defgroup UART_State UART State + * @{ + */ +#define UART_STATE_DISABLE 0x00000000U +#define UART_STATE_ENABLE ((uint32_t)USART_CR1_UE) +/** + * @} + */ + +/** @defgroup UART_Over_Sampling UART Over Sampling + * @{ + */ +#define UART_OVERSAMPLING_16 0x00000000U +#define UART_OVERSAMPLING_8 ((uint32_t)USART_CR1_OVER8) +/** + * @} + */ + +/** @defgroup UART_LIN_Break_Detection_Length UART LIN Break Detection Length + * @{ + */ +#define UART_LINBREAKDETECTLENGTH_10B 0x00000000U +#define UART_LINBREAKDETECTLENGTH_11B ((uint32_t)USART_CR2_LBDL) +/** + * @} + */ + +/** @defgroup UART_WakeUp_functions UART Wakeup Functions + * @{ + */ +#define UART_WAKEUPMETHOD_IDLELINE 0x00000000U +#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE) +/** + * @} + */ + +/** @defgroup UART_Flags UART FLags + * Elements values convention: 0xXXXX + * - 0xXXXX : Flag mask in the SR register + * @{ + */ +#define UART_FLAG_CTS ((uint32_t)USART_SR_CTS) +#define UART_FLAG_LBD ((uint32_t)USART_SR_LBD) +#define UART_FLAG_TXE ((uint32_t)USART_SR_TXE) +#define UART_FLAG_TC ((uint32_t)USART_SR_TC) +#define UART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) +#define UART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) +#define UART_FLAG_ORE ((uint32_t)USART_SR_ORE) +#define UART_FLAG_NE ((uint32_t)USART_SR_NE) +#define UART_FLAG_FE ((uint32_t)USART_SR_FE) +#define UART_FLAG_PE ((uint32_t)USART_SR_PE) +/** + * @} + */ + +/** @defgroup UART_Interrupt_definition UART Interrupt Definitions + * Elements values convention: 0xY000XXXX + * - XXXX : Interrupt mask (16 bits) in the Y register + * - Y : Interrupt source register (2bits) + * - 0001: CR1 register + * - 0010: CR2 register + * - 0011: CR3 register + * @{ + */ + +#define UART_IT_PE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) +#define UART_IT_TXE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) +#define UART_IT_TC ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) +#define UART_IT_RXNE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) +#define UART_IT_IDLE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) + +#define UART_IT_LBD ((uint32_t)(UART_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) + +#define UART_IT_CTS ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) +#define UART_IT_ERR ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) +/** + * @} + */ + +/** @defgroup UART_RECEPTION_TYPE_Values UART Reception type values + * @{ + */ +#define HAL_UART_RECEPTION_STANDARD (0x00000000U) /*!< Standard reception */ +#define HAL_UART_RECEPTION_TOIDLE (0x00000001U) /*!< Reception till completion or IDLE event */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup UART_Exported_Macros UART Exported Macros + * @{ + */ + +/** @brief Reset UART handle gstate & RxState + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ + (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ + (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ + (__HANDLE__)->MspInitCallback = NULL; \ + (__HANDLE__)->MspDeInitCallback = NULL; \ + } while(0U) +#else +#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ + (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ + (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ + } while(0U) +#endif /*USE_HAL_UART_REGISTER_CALLBACKS */ + +/** @brief Flushes the UART DR register + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + */ +#define __HAL_UART_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) + +/** @brief Checks whether the specified UART flag is set or not. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @param __FLAG__ specifies the flag to check. + * This parameter can be one of the following values: + * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) + * @arg UART_FLAG_LBD: LIN Break detection flag + * @arg UART_FLAG_TXE: Transmit data register empty flag + * @arg UART_FLAG_TC: Transmission Complete flag + * @arg UART_FLAG_RXNE: Receive data register not empty flag + * @arg UART_FLAG_IDLE: Idle Line detection flag + * @arg UART_FLAG_ORE: Overrun Error flag + * @arg UART_FLAG_NE: Noise Error flag + * @arg UART_FLAG_FE: Framing Error flag + * @arg UART_FLAG_PE: Parity Error flag + * @retval The new state of __FLAG__ (TRUE or FALSE). + */ +#define __HAL_UART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) + +/** @brief Clears the specified UART pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @param __FLAG__ specifies the flag to check. + * This parameter can be any combination of the following values: + * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). + * @arg UART_FLAG_LBD: LIN Break detection flag. + * @arg UART_FLAG_TC: Transmission Complete flag. + * @arg UART_FLAG_RXNE: Receive data register not empty flag. + * + * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun + * error) and IDLE (Idle line detected) flags are cleared by software + * sequence: a read operation to USART_SR register followed by a read + * operation to USART_DR register. + * @note RXNE flag can be also cleared by a read to the USART_DR register. + * @note TC flag can be also cleared by software sequence: a read operation to + * USART_SR register followed by a write operation to USART_DR register. + * @note TXE flag is cleared only by a write to the USART_DR register. + * + * @retval None + */ +#define __HAL_UART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) + +/** @brief Clears the UART PE pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#define __HAL_UART_CLEAR_PEFLAG(__HANDLE__) \ + do{ \ + __IO uint32_t tmpreg = 0x00U; \ + tmpreg = (__HANDLE__)->Instance->SR; \ + tmpreg = (__HANDLE__)->Instance->DR; \ + UNUSED(tmpreg); \ + } while(0U) + +/** @brief Clears the UART FE pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#define __HAL_UART_CLEAR_FEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) + +/** @brief Clears the UART NE pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#define __HAL_UART_CLEAR_NEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) + +/** @brief Clears the UART ORE pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#define __HAL_UART_CLEAR_OREFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) + +/** @brief Clears the UART IDLE pending flag. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @retval None + */ +#define __HAL_UART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) + +/** @brief Enable the specified UART interrupt. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @param __INTERRUPT__ specifies the UART interrupt source to enable. + * This parameter can be one of the following values: + * @arg UART_IT_CTS: CTS change interrupt + * @arg UART_IT_LBD: LIN Break detection interrupt + * @arg UART_IT_TXE: Transmit Data Register empty interrupt + * @arg UART_IT_TC: Transmission complete interrupt + * @arg UART_IT_RXNE: Receive Data register not empty interrupt + * @arg UART_IT_IDLE: Idle line detection interrupt + * @arg UART_IT_PE: Parity Error interrupt + * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @retval None + */ +#define __HAL_UART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & UART_IT_MASK)): \ + (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & UART_IT_MASK)): \ + ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & UART_IT_MASK))) + +/** @brief Disable the specified UART interrupt. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @param __INTERRUPT__ specifies the UART interrupt source to disable. + * This parameter can be one of the following values: + * @arg UART_IT_CTS: CTS change interrupt + * @arg UART_IT_LBD: LIN Break detection interrupt + * @arg UART_IT_TXE: Transmit Data Register empty interrupt + * @arg UART_IT_TC: Transmission complete interrupt + * @arg UART_IT_RXNE: Receive Data register not empty interrupt + * @arg UART_IT_IDLE: Idle line detection interrupt + * @arg UART_IT_PE: Parity Error interrupt + * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @retval None + */ +#define __HAL_UART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ + (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ + ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & UART_IT_MASK))) + +/** @brief Checks whether the specified UART interrupt source is enabled or not. + * @param __HANDLE__ specifies the UART Handle. + * UART Handle selects the USARTx or UARTy peripheral + * (USART,UART availability and x,y values depending on device). + * @param __IT__ specifies the UART interrupt source to check. + * This parameter can be one of the following values: + * @arg UART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg UART_IT_LBD: LIN Break detection interrupt + * @arg UART_IT_TXE: Transmit Data Register empty interrupt + * @arg UART_IT_TC: Transmission complete interrupt + * @arg UART_IT_RXNE: Receive Data register not empty interrupt + * @arg UART_IT_IDLE: Idle line detection interrupt + * @arg UART_IT_ERR: Error interrupt + * @retval The new state of __IT__ (TRUE or FALSE). + */ +#define __HAL_UART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == UART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == UART_CR2_REG_INDEX)? \ + (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & UART_IT_MASK)) + +/** @brief Enable CTS flow control + * @note This macro allows to enable CTS hardware flow control for a given UART instance, + * without need to call HAL_UART_Init() function. + * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. + * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need + * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : + * - UART instance should have already been initialised (through call of HAL_UART_Init() ) + * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) + * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). + * @param __HANDLE__ specifies the UART Handle. + * The Handle Instance can be any USARTx (supporting the HW Flow control feature). + * It is used to select the USART peripheral (USART availability and x value depending on device). + * @retval None + */ +#define __HAL_UART_HWCONTROL_CTS_ENABLE(__HANDLE__) \ + do{ \ + ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ + (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_CTSE; \ + } while(0U) + +/** @brief Disable CTS flow control + * @note This macro allows to disable CTS hardware flow control for a given UART instance, + * without need to call HAL_UART_Init() function. + * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. + * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need + * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : + * - UART instance should have already been initialised (through call of HAL_UART_Init() ) + * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) + * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). + * @param __HANDLE__ specifies the UART Handle. + * The Handle Instance can be any USARTx (supporting the HW Flow control feature). + * It is used to select the USART peripheral (USART availability and x value depending on device). + * @retval None + */ +#define __HAL_UART_HWCONTROL_CTS_DISABLE(__HANDLE__) \ + do{ \ + ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ + (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_CTSE); \ + } while(0U) + +/** @brief Enable RTS flow control + * This macro allows to enable RTS hardware flow control for a given UART instance, + * without need to call HAL_UART_Init() function. + * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. + * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need + * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : + * - UART instance should have already been initialised (through call of HAL_UART_Init() ) + * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) + * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). + * @param __HANDLE__ specifies the UART Handle. + * The Handle Instance can be any USARTx (supporting the HW Flow control feature). + * It is used to select the USART peripheral (USART availability and x value depending on device). + * @retval None + */ +#define __HAL_UART_HWCONTROL_RTS_ENABLE(__HANDLE__) \ + do{ \ + ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE); \ + (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_RTSE; \ + } while(0U) + +/** @brief Disable RTS flow control + * This macro allows to disable RTS hardware flow control for a given UART instance, + * without need to call HAL_UART_Init() function. + * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. + * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need + * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : + * - UART instance should have already been initialised (through call of HAL_UART_Init() ) + * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) + * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). + * @param __HANDLE__ specifies the UART Handle. + * The Handle Instance can be any USARTx (supporting the HW Flow control feature). + * It is used to select the USART peripheral (USART availability and x value depending on device). + * @retval None + */ +#define __HAL_UART_HWCONTROL_RTS_DISABLE(__HANDLE__) \ + do{ \ + ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE);\ + (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_RTSE); \ + } while(0U) + +/** @brief Macro to enable the UART's one bit sample method + * @param __HANDLE__ specifies the UART Handle. + * @retval None + */ +#define __HAL_UART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) + +/** @brief Macro to disable the UART's one bit sample method + * @param __HANDLE__ specifies the UART Handle. + * @retval None + */ +#define __HAL_UART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ + &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) + +/** @brief Enable UART + * @param __HANDLE__ specifies the UART Handle. + * @retval None + */ +#define __HAL_UART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) + +/** @brief Disable UART + * @param __HANDLE__ specifies the UART Handle. + * @retval None + */ +#define __HAL_UART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup UART_Exported_Functions + * @{ + */ + +/** @addtogroup UART_Exported_Functions_Group1 Initialization and de-initialization functions + * @{ + */ + +/* Initialization/de-initialization functions **********************************/ +HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength); +HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod); +HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart); +void HAL_UART_MspInit(UART_HandleTypeDef *huart); +void HAL_UART_MspDeInit(UART_HandleTypeDef *huart); + +/* Callbacks Register/UnRegister functions ***********************************/ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, + pUART_CallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID); + +HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback); +HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @addtogroup UART_Exported_Functions_Group2 IO operation functions + * @{ + */ + +/* IO operation functions *******************************************************/ +HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); +HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart); + +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, + uint32_t Timeout); +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); + +/* Transfer Abort functions */ +HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart); + +void HAL_UART_IRQHandler(UART_HandleTypeDef *huart); +void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart); +void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart); +void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart); + +void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size); + +/** + * @} + */ + +/** @addtogroup UART_Exported_Functions_Group3 + * @{ + */ +/* Peripheral Control functions ************************************************/ +HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart); +HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart); +/** + * @} + */ + +/** @addtogroup UART_Exported_Functions_Group4 + * @{ + */ +/* Peripheral State functions **************************************************/ +HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart); +uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart); +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup UART_Private_Constants UART Private Constants + * @{ + */ +/** @brief UART interruptions flag mask + * + */ +#define UART_IT_MASK 0x0000FFFFU + +#define UART_CR1_REG_INDEX 1U +#define UART_CR2_REG_INDEX 2U +#define UART_CR3_REG_INDEX 3U +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup UART_Private_Macros UART Private Macros + * @{ + */ +#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B) || \ + ((LENGTH) == UART_WORDLENGTH_9B)) +#define IS_UART_LIN_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B)) +#define IS_UART_STOPBITS(STOPBITS) (((STOPBITS) == UART_STOPBITS_1) || \ + ((STOPBITS) == UART_STOPBITS_2)) +#define IS_UART_PARITY(PARITY) (((PARITY) == UART_PARITY_NONE) || \ + ((PARITY) == UART_PARITY_EVEN) || \ + ((PARITY) == UART_PARITY_ODD)) +#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == UART_HWCONTROL_NONE) || \ + ((CONTROL) == UART_HWCONTROL_RTS) || \ + ((CONTROL) == UART_HWCONTROL_CTS) || \ + ((CONTROL) == UART_HWCONTROL_RTS_CTS)) +#define IS_UART_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00U)) +#define IS_UART_STATE(STATE) (((STATE) == UART_STATE_DISABLE) || \ + ((STATE) == UART_STATE_ENABLE)) +#define IS_UART_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16) || \ + ((SAMPLING) == UART_OVERSAMPLING_8)) +#define IS_UART_LIN_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16)) +#define IS_UART_LIN_BREAK_DETECT_LENGTH(LENGTH) (((LENGTH) == UART_LINBREAKDETECTLENGTH_10B) || \ + ((LENGTH) == UART_LINBREAKDETECTLENGTH_11B)) +#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \ + ((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK)) +#define IS_UART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 10500000U) +#define IS_UART_ADDRESS(ADDRESS) ((ADDRESS) <= 0x0FU) + +#define UART_DIV_SAMPLING16(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*((uint64_t)(_BAUD_))))) +#define UART_DIVMANT_SAMPLING16(_PCLK_, _BAUD_) (UART_DIV_SAMPLING16((_PCLK_), (_BAUD_))/100U) +#define UART_DIVFRAQ_SAMPLING16(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING16((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) * 100U)) * 16U)\ + + 50U) / 100U) +/* UART BRR = mantissa + overflow + fraction + = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ +#define UART_BRR_SAMPLING16(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) << 4U) + \ + (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0xF0U) + \ + (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0x0FU)) + +#define UART_DIV_SAMPLING8(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) +#define UART_DIVMANT_SAMPLING8(_PCLK_, _BAUD_) (UART_DIV_SAMPLING8((_PCLK_), (_BAUD_))/100U) +#define UART_DIVFRAQ_SAMPLING8(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING8((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) * 100U)) * 8U)\ + + 50U) / 100U) +/* UART BRR = mantissa + overflow + fraction + = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ +#define UART_BRR_SAMPLING8(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) << 4U) + \ + ((UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0xF8U) << 1U) + \ + (UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0x07U)) + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup UART_Private_Functions UART Private Functions + * @{ + */ + +HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); +HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_UART_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h new file mode 100644 index 0000000..942e1c3 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h @@ -0,0 +1,4779 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_adc.h + * @author MCD Application Team + * @brief Header file of ADC LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_ADC_H +#define __STM32F4xx_LL_ADC_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (ADC1) || defined (ADC2) || defined (ADC3) + +/** @defgroup ADC_LL ADC + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup ADC_LL_Private_Constants ADC Private Constants + * @{ + */ + +/* Internal mask for ADC group regular sequencer: */ +/* To select into literal LL_ADC_REG_RANK_x the relevant bits for: */ +/* - sequencer register offset */ +/* - sequencer rank bits position into the selected register */ + +/* Internal register offset for ADC group regular sequencer configuration */ +/* (offset placed into a spare area of literal definition) */ +#define ADC_SQR1_REGOFFSET 0x00000000UL +#define ADC_SQR2_REGOFFSET 0x00000100UL +#define ADC_SQR3_REGOFFSET 0x00000200UL +#define ADC_SQR4_REGOFFSET 0x00000300UL + +#define ADC_REG_SQRX_REGOFFSET_MASK (ADC_SQR1_REGOFFSET | ADC_SQR2_REGOFFSET | ADC_SQR3_REGOFFSET | ADC_SQR4_REGOFFSET) +#define ADC_REG_RANK_ID_SQRX_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) + +/* Definition of ADC group regular sequencer bits information to be inserted */ +/* into ADC group regular sequencer ranks literals definition. */ +#define ADC_REG_RANK_1_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ1) */ +#define ADC_REG_RANK_2_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ2) */ +#define ADC_REG_RANK_3_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ3) */ +#define ADC_REG_RANK_4_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ4) */ +#define ADC_REG_RANK_5_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ5) */ +#define ADC_REG_RANK_6_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ6) */ +#define ADC_REG_RANK_7_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ7) */ +#define ADC_REG_RANK_8_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ8) */ +#define ADC_REG_RANK_9_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ9) */ +#define ADC_REG_RANK_10_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ10) */ +#define ADC_REG_RANK_11_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ11) */ +#define ADC_REG_RANK_12_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ12) */ +#define ADC_REG_RANK_13_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ13) */ +#define ADC_REG_RANK_14_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ14) */ +#define ADC_REG_RANK_15_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ15) */ +#define ADC_REG_RANK_16_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ16) */ + +/* Internal mask for ADC group injected sequencer: */ +/* To select into literal LL_ADC_INJ_RANK_x the relevant bits for: */ +/* - data register offset */ +/* - offset register offset */ +/* - sequencer rank bits position into the selected register */ + +/* Internal register offset for ADC group injected data register */ +/* (offset placed into a spare area of literal definition) */ +#define ADC_JDR1_REGOFFSET 0x00000000UL +#define ADC_JDR2_REGOFFSET 0x00000100UL +#define ADC_JDR3_REGOFFSET 0x00000200UL +#define ADC_JDR4_REGOFFSET 0x00000300UL + +/* Internal register offset for ADC group injected offset configuration */ +/* (offset placed into a spare area of literal definition) */ +#define ADC_JOFR1_REGOFFSET 0x00000000UL +#define ADC_JOFR2_REGOFFSET 0x00001000UL +#define ADC_JOFR3_REGOFFSET 0x00002000UL +#define ADC_JOFR4_REGOFFSET 0x00003000UL + +#define ADC_INJ_JDRX_REGOFFSET_MASK (ADC_JDR1_REGOFFSET | ADC_JDR2_REGOFFSET | ADC_JDR3_REGOFFSET | ADC_JDR4_REGOFFSET) +#define ADC_INJ_JOFRX_REGOFFSET_MASK (ADC_JOFR1_REGOFFSET | ADC_JOFR2_REGOFFSET | ADC_JOFR3_REGOFFSET | ADC_JOFR4_REGOFFSET) +#define ADC_INJ_RANK_ID_JSQR_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) + +/* Internal mask for ADC group regular trigger: */ +/* To select into literal LL_ADC_REG_TRIG_x the relevant bits for: */ +/* - regular trigger source */ +/* - regular trigger edge */ +#define ADC_REG_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_EXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ + +/* Mask containing trigger source masks for each of possible */ +/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ +/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ +#define ADC_REG_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTSEL) >> (4UL * 0UL)) | \ + ((ADC_CR2_EXTSEL) >> (4UL * 1UL)) | \ + ((ADC_CR2_EXTSEL) >> (4UL * 2UL)) | \ + ((ADC_CR2_EXTSEL) >> (4UL * 3UL))) + +/* Mask containing trigger edge masks for each of possible */ +/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ +/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ +#define ADC_REG_TRIG_EDGE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN) >> (4UL * 0UL)) | \ + ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ + ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ + ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) + +/* Definition of ADC group regular trigger bits information. */ +#define ADC_REG_TRIG_EXTSEL_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTSEL) */ +#define ADC_REG_TRIG_EXTEN_BITOFFSET_POS (28UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTEN) */ + + + +/* Internal mask for ADC group injected trigger: */ +/* To select into literal LL_ADC_INJ_TRIG_x the relevant bits for: */ +/* - injected trigger source */ +/* - injected trigger edge */ +#define ADC_INJ_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_JEXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ + +/* Mask containing trigger source masks for each of possible */ +/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ +/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ +#define ADC_INJ_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_JEXTSEL) >> (4UL * 0UL)) | \ + ((ADC_CR2_JEXTSEL) >> (4UL * 1UL)) | \ + ((ADC_CR2_JEXTSEL) >> (4UL * 2UL)) | \ + ((ADC_CR2_JEXTSEL) >> (4UL * 3UL))) + +/* Mask containing trigger edge masks for each of possible */ +/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ +/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ +#define ADC_INJ_TRIG_EDGE_MASK (((LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN) >> (4UL * 0UL)) | \ + ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ + ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ + ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) + +/* Definition of ADC group injected trigger bits information. */ +#define ADC_INJ_TRIG_EXTSEL_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTSEL) */ +#define ADC_INJ_TRIG_EXTEN_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTEN) */ + +/* Internal mask for ADC channel: */ +/* To select into literal LL_ADC_CHANNEL_x the relevant bits for: */ +/* - channel identifier defined by number */ +/* - channel differentiation between external channels (connected to */ +/* GPIO pins) and internal channels (connected to internal paths) */ +/* - channel sampling time defined by SMPRx register offset */ +/* and SMPx bits positions into SMPRx register */ +#define ADC_CHANNEL_ID_NUMBER_MASK (ADC_CR1_AWDCH) +#define ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS ( 0UL)/* Value equivalent to POSITION_VAL(ADC_CHANNEL_ID_NUMBER_MASK) */ +#define ADC_CHANNEL_ID_MASK (ADC_CHANNEL_ID_NUMBER_MASK | ADC_CHANNEL_ID_INTERNAL_CH_MASK) +/* Equivalent mask of ADC_CHANNEL_NUMBER_MASK aligned on register LSB (bit 0) */ +#define ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0 0x0000001FU /* Equivalent to shift: (ADC_CHANNEL_NUMBER_MASK >> POSITION_VAL(ADC_CHANNEL_NUMBER_MASK)) */ + +/* Channel differentiation between external and internal channels */ +#define ADC_CHANNEL_ID_INTERNAL_CH 0x80000000UL /* Marker of internal channel */ +#define ADC_CHANNEL_ID_INTERNAL_CH_2 0x40000000UL /* Marker of internal channel for other ADC instances, in case of different ADC internal channels mapped on same channel number on different ADC instances */ +#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ +#define ADC_CHANNEL_ID_INTERNAL_CH_MASK (ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_ID_INTERNAL_CH_2 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) + +/* Internal register offset for ADC channel sampling time configuration */ +/* (offset placed into a spare area of literal definition) */ +#define ADC_SMPR1_REGOFFSET 0x00000000UL +#define ADC_SMPR2_REGOFFSET 0x02000000UL +#define ADC_CHANNEL_SMPRX_REGOFFSET_MASK (ADC_SMPR1_REGOFFSET | ADC_SMPR2_REGOFFSET) + +#define ADC_CHANNEL_SMPx_BITOFFSET_MASK 0x01F00000UL +#define ADC_CHANNEL_SMPx_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CHANNEL_SMPx_BITOFFSET_MASK) */ + +/* Definition of channels ID number information to be inserted into */ +/* channels literals definition. */ +#define ADC_CHANNEL_0_NUMBER 0x00000000UL +#define ADC_CHANNEL_1_NUMBER ( ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_2_NUMBER ( ADC_CR1_AWDCH_1 ) +#define ADC_CHANNEL_3_NUMBER ( ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_4_NUMBER ( ADC_CR1_AWDCH_2 ) +#define ADC_CHANNEL_5_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_6_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) +#define ADC_CHANNEL_7_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_8_NUMBER ( ADC_CR1_AWDCH_3 ) +#define ADC_CHANNEL_9_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_10_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 ) +#define ADC_CHANNEL_11_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_12_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 ) +#define ADC_CHANNEL_13_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_14_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) +#define ADC_CHANNEL_15_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_16_NUMBER (ADC_CR1_AWDCH_4 ) +#define ADC_CHANNEL_17_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0) +#define ADC_CHANNEL_18_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1 ) + +/* Definition of channels sampling time information to be inserted into */ +/* channels literals definition. */ +#define ADC_CHANNEL_0_SMP (ADC_SMPR2_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP0) */ +#define ADC_CHANNEL_1_SMP (ADC_SMPR2_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP1) */ +#define ADC_CHANNEL_2_SMP (ADC_SMPR2_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP2) */ +#define ADC_CHANNEL_3_SMP (ADC_SMPR2_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP3) */ +#define ADC_CHANNEL_4_SMP (ADC_SMPR2_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP4) */ +#define ADC_CHANNEL_5_SMP (ADC_SMPR2_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP5) */ +#define ADC_CHANNEL_6_SMP (ADC_SMPR2_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP6) */ +#define ADC_CHANNEL_7_SMP (ADC_SMPR2_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP7) */ +#define ADC_CHANNEL_8_SMP (ADC_SMPR2_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP8) */ +#define ADC_CHANNEL_9_SMP (ADC_SMPR2_REGOFFSET | ((27UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP9) */ +#define ADC_CHANNEL_10_SMP (ADC_SMPR1_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP10) */ +#define ADC_CHANNEL_11_SMP (ADC_SMPR1_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP11) */ +#define ADC_CHANNEL_12_SMP (ADC_SMPR1_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP12) */ +#define ADC_CHANNEL_13_SMP (ADC_SMPR1_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP13) */ +#define ADC_CHANNEL_14_SMP (ADC_SMPR1_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP14) */ +#define ADC_CHANNEL_15_SMP (ADC_SMPR1_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP15) */ +#define ADC_CHANNEL_16_SMP (ADC_SMPR1_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP16) */ +#define ADC_CHANNEL_17_SMP (ADC_SMPR1_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP17) */ +#define ADC_CHANNEL_18_SMP (ADC_SMPR1_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP18) */ + +/* Internal mask for ADC analog watchdog: */ +/* To select into literals LL_ADC_AWD_CHANNELx_xxx the relevant bits for: */ +/* (concatenation of multiple bits used in different analog watchdogs, */ +/* (feature of several watchdogs not available on all STM32 families)). */ +/* - analog watchdog 1: monitored channel defined by number, */ +/* selection of ADC group (ADC groups regular and-or injected). */ + +/* Internal register offset for ADC analog watchdog channel configuration */ +#define ADC_AWD_CR1_REGOFFSET 0x00000000UL + +#define ADC_AWD_CRX_REGOFFSET_MASK (ADC_AWD_CR1_REGOFFSET) + +#define ADC_AWD_CR1_CHANNEL_MASK (ADC_CR1_AWDCH | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) +#define ADC_AWD_CR_ALL_CHANNEL_MASK (ADC_AWD_CR1_CHANNEL_MASK) + +/* Internal register offset for ADC analog watchdog threshold configuration */ +#define ADC_AWD_TR1_HIGH_REGOFFSET 0x00000000UL +#define ADC_AWD_TR1_LOW_REGOFFSET 0x00000001UL +#define ADC_AWD_TRX_REGOFFSET_MASK (ADC_AWD_TR1_HIGH_REGOFFSET | ADC_AWD_TR1_LOW_REGOFFSET) + +/* ADC registers bits positions */ +#define ADC_CR1_RES_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR1_RES) */ +#define ADC_TR_HT_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_TR_HT) */ + +/* ADC internal channels related definitions */ +/* Internal voltage reference VrefInt */ +#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FFF7A2AU)) /* Internal voltage reference, address of parameter VREFINT_CAL: VrefInt ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ +#define VREFINT_CAL_VREF ( 3300UL) /* Analog voltage reference (Vref+) value with which temperature sensor has been calibrated in production (tolerance: +-10 mV) (unit: mV). */ +/* Temperature sensor */ +#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FFF7A2CU)) /* Internal temperature sensor, address of parameter TS_CAL1: On STM32F4, temperature sensor ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ +#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FFF7A2EU)) /* Internal temperature sensor, address of parameter TS_CAL2: On STM32F4, temperature sensor ADC raw data acquired at temperature 110 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ +#define TEMPSENSOR_CAL1_TEMP (( int32_t) 30) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL1_ADDR (tolerance: +-5 DegC) (unit: DegC). */ +#define TEMPSENSOR_CAL2_TEMP (( int32_t) 110) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL2_ADDR (tolerance: +-5 DegC) (unit: DegC). */ +#define TEMPSENSOR_CAL_VREFANALOG ( 3300UL) /* Analog voltage reference (Vref+) voltage with which temperature sensor has been calibrated in production (+-10 mV) (unit: mV). */ + +/** + * @} + */ + + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup ADC_LL_Private_Macros ADC Private Macros + * @{ + */ + +/** + * @brief Driver macro reserved for internal use: isolate bits with the + * selected mask and shift them to the register LSB + * (shift mask on register position bit 0). + * @param __BITS__ Bits in register 32 bits + * @param __MASK__ Mask in register 32 bits + * @retval Bits in register 32 bits + */ +#define __ADC_MASK_SHIFT(__BITS__, __MASK__) \ + (((__BITS__) & (__MASK__)) >> POSITION_VAL((__MASK__))) + +/** + * @brief Driver macro reserved for internal use: set a pointer to + * a register from a register basis from which an offset + * is applied. + * @param __REG__ Register basis from which the offset is applied. + * @param __REG_OFFFSET__ Offset to be applied (unit number of registers). + * @retval Pointer to register address + */ +#define __ADC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \ + ((__IO uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2UL)))) + +/** + * @} + */ + + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup ADC_LL_ES_INIT ADC Exported Init structure + * @{ + */ + +/** + * @brief Structure definition of some features of ADC common parameters + * and multimode + * (all ADC instances belonging to the same ADC common instance). + * @note The setting of these parameters by function @ref LL_ADC_CommonInit() + * is conditioned to ADC instances state (all ADC instances + * sharing the same ADC common instance): + * All ADC instances sharing the same ADC common instance must be + * disabled. + */ +typedef struct +{ + uint32_t CommonClock; /*!< Set parameter common to several ADC: Clock source and prescaler. + This parameter can be a value of @ref ADC_LL_EC_COMMON_CLOCK_SOURCE + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetCommonClock(). */ + +#if defined(ADC_MULTIMODE_SUPPORT) + uint32_t Multimode; /*!< Set ADC multimode configuration to operate in independent mode or multimode (for devices with several ADC instances). + This parameter can be a value of @ref ADC_LL_EC_MULTI_MODE + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultimode(). */ + + uint32_t MultiDMATransfer; /*!< Set ADC multimode conversion data transfer: no transfer or transfer by DMA. + This parameter can be a value of @ref ADC_LL_EC_MULTI_DMA_TRANSFER + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiDMATransfer(). */ + + uint32_t MultiTwoSamplingDelay; /*!< Set ADC multimode delay between 2 sampling phases. + This parameter can be a value of @ref ADC_LL_EC_MULTI_TWOSMP_DELAY + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiTwoSamplingDelay(). */ +#endif /* ADC_MULTIMODE_SUPPORT */ + +} LL_ADC_CommonInitTypeDef; + +/** + * @brief Structure definition of some features of ADC instance. + * @note These parameters have an impact on ADC scope: ADC instance. + * Affects both group regular and group injected (availability + * of ADC group injected depends on STM32 families). + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Instance . + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + */ +typedef struct +{ + uint32_t Resolution; /*!< Set ADC resolution. + This parameter can be a value of @ref ADC_LL_EC_RESOLUTION + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetResolution(). */ + + uint32_t DataAlignment; /*!< Set ADC conversion data alignment. + This parameter can be a value of @ref ADC_LL_EC_DATA_ALIGN + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetDataAlignment(). */ + + uint32_t SequencersScanMode; /*!< Set ADC scan selection. + This parameter can be a value of @ref ADC_LL_EC_SCAN_SELECTION + + This feature can be modified afterwards using unitary function @ref LL_ADC_SetSequencersScanMode(). */ + +} LL_ADC_InitTypeDef; + +/** + * @brief Structure definition of some features of ADC group regular. + * @note These parameters have an impact on ADC scope: ADC group regular. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "REG"). + * @note The setting of these parameters by function @ref LL_ADC_REG_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + */ +typedef struct +{ + uint32_t TriggerSource; /*!< Set ADC group regular conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). + This parameter can be a value of @ref ADC_LL_EC_REG_TRIGGER_SOURCE + @note On this STM32 series, setting of external trigger edge is performed + using function @ref LL_ADC_REG_StartConversionExtTrig(). + + This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetTriggerSource(). */ + + uint32_t SequencerLength; /*!< Set ADC group regular sequencer length. + This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_SCAN_LENGTH + @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). + + This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerLength(). */ + + uint32_t SequencerDiscont; /*!< Set ADC group regular sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. + This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_DISCONT_MODE + @note This parameter has an effect only if group regular sequencer is enabled + (scan length of 2 ranks or more). + + This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerDiscont(). */ + + uint32_t ContinuousMode; /*!< Set ADC continuous conversion mode on ADC group regular, whether ADC conversions are performed in single mode (one conversion per trigger) or in continuous mode (after the first trigger, following conversions launched successively automatically). + This parameter can be a value of @ref ADC_LL_EC_REG_CONTINUOUS_MODE + Note: It is not possible to enable both ADC group regular continuous mode and discontinuous mode. + + This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetContinuousMode(). */ + + uint32_t DMATransfer; /*!< Set ADC group regular conversion data transfer: no transfer or transfer by DMA, and DMA requests mode. + This parameter can be a value of @ref ADC_LL_EC_REG_DMA_TRANSFER + + This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetDMATransfer(). */ + +} LL_ADC_REG_InitTypeDef; + +/** + * @brief Structure definition of some features of ADC group injected. + * @note These parameters have an impact on ADC scope: ADC group injected. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "INJ"). + * @note The setting of these parameters by function @ref LL_ADC_INJ_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + */ +typedef struct +{ + uint32_t TriggerSource; /*!< Set ADC group injected conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). + This parameter can be a value of @ref ADC_LL_EC_INJ_TRIGGER_SOURCE + @note On this STM32 series, setting of external trigger edge is performed + using function @ref LL_ADC_INJ_StartConversionExtTrig(). + + This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTriggerSource(). */ + + uint32_t SequencerLength; /*!< Set ADC group injected sequencer length. + This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_SCAN_LENGTH + @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). + + This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerLength(). */ + + uint32_t SequencerDiscont; /*!< Set ADC group injected sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. + This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_DISCONT_MODE + @note This parameter has an effect only if group injected sequencer is enabled + (scan length of 2 ranks or more). + + This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerDiscont(). */ + + uint32_t TrigAuto; /*!< Set ADC group injected conversion trigger: independent or from ADC group regular. + This parameter can be a value of @ref ADC_LL_EC_INJ_TRIG_AUTO + Note: This parameter must be set to set to independent trigger if injected trigger source is set to an external trigger. + + This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTrigAuto(). */ + +} LL_ADC_INJ_InitTypeDef; + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup ADC_LL_Exported_Constants ADC Exported Constants + * @{ + */ + +/** @defgroup ADC_LL_EC_FLAG ADC flags + * @brief Flags defines which can be used with LL_ADC_ReadReg function + * @{ + */ +#define LL_ADC_FLAG_STRT ADC_SR_STRT /*!< ADC flag ADC group regular conversion start */ +#define LL_ADC_FLAG_EOCS ADC_SR_EOC /*!< ADC flag ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ +#define LL_ADC_FLAG_OVR ADC_SR_OVR /*!< ADC flag ADC group regular overrun */ +#define LL_ADC_FLAG_JSTRT ADC_SR_JSTRT /*!< ADC flag ADC group injected conversion start */ +#define LL_ADC_FLAG_JEOS ADC_SR_JEOC /*!< ADC flag ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ +#define LL_ADC_FLAG_AWD1 ADC_SR_AWD /*!< ADC flag ADC analog watchdog 1 */ +#if defined(ADC_MULTIMODE_SUPPORT) +#define LL_ADC_FLAG_EOCS_MST ADC_CSR_EOC1 /*!< ADC flag ADC multimode master group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ +#define LL_ADC_FLAG_EOCS_SLV1 ADC_CSR_EOC2 /*!< ADC flag ADC multimode slave 1 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ +#define LL_ADC_FLAG_EOCS_SLV2 ADC_CSR_EOC3 /*!< ADC flag ADC multimode slave 2 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ +#define LL_ADC_FLAG_OVR_MST ADC_CSR_OVR1 /*!< ADC flag ADC multimode master group regular overrun */ +#define LL_ADC_FLAG_OVR_SLV1 ADC_CSR_OVR2 /*!< ADC flag ADC multimode slave 1 group regular overrun */ +#define LL_ADC_FLAG_OVR_SLV2 ADC_CSR_OVR3 /*!< ADC flag ADC multimode slave 2 group regular overrun */ +#define LL_ADC_FLAG_JEOS_MST ADC_CSR_JEOC1 /*!< ADC flag ADC multimode master group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ +#define LL_ADC_FLAG_JEOS_SLV1 ADC_CSR_JEOC2 /*!< ADC flag ADC multimode slave 1 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ +#define LL_ADC_FLAG_JEOS_SLV2 ADC_CSR_JEOC3 /*!< ADC flag ADC multimode slave 2 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ +#define LL_ADC_FLAG_AWD1_MST ADC_CSR_AWD1 /*!< ADC flag ADC multimode master analog watchdog 1 of the ADC master */ +#define LL_ADC_FLAG_AWD1_SLV1 ADC_CSR_AWD2 /*!< ADC flag ADC multimode slave 1 analog watchdog 1 */ +#define LL_ADC_FLAG_AWD1_SLV2 ADC_CSR_AWD3 /*!< ADC flag ADC multimode slave 2 analog watchdog 1 */ +#endif +/** + * @} + */ + +/** @defgroup ADC_LL_EC_IT ADC interruptions for configuration (interruption enable or disable) + * @brief IT defines which can be used with LL_ADC_ReadReg and LL_ADC_WriteReg functions + * @{ + */ +#define LL_ADC_IT_EOCS ADC_CR1_EOCIE /*!< ADC interruption ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ +#define LL_ADC_IT_OVR ADC_CR1_OVRIE /*!< ADC interruption ADC group regular overrun */ +#define LL_ADC_IT_JEOS ADC_CR1_JEOCIE /*!< ADC interruption ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ +#define LL_ADC_IT_AWD1 ADC_CR1_AWDIE /*!< ADC interruption ADC analog watchdog 1 */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REGISTERS ADC registers compliant with specific purpose + * @{ + */ +/* List of ADC registers intended to be used (most commonly) with */ +/* DMA transfer. */ +/* Refer to function @ref LL_ADC_DMA_GetRegAddr(). */ +#define LL_ADC_DMA_REG_REGULAR_DATA 0x00000000UL /* ADC group regular conversion data register (corresponding to register DR) to be used with ADC configured in independent mode. Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadConversionData32() and other functions @ref LL_ADC_REG_ReadConversionDatax() */ +#if defined(ADC_MULTIMODE_SUPPORT) +#define LL_ADC_DMA_REG_REGULAR_DATA_MULTI 0x00000001UL /* ADC group regular conversion data register (corresponding to register CDR) to be used with ADC configured in multimode (available on STM32 devices with several ADC instances). Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadMultiConversionData32() */ +#endif +/** + * @} + */ + +/** @defgroup ADC_LL_EC_COMMON_CLOCK_SOURCE ADC common - Clock source + * @{ + */ +#define LL_ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000UL /*!< ADC synchronous clock derived from AHB clock with prescaler division by 2 */ +#define LL_ADC_CLOCK_SYNC_PCLK_DIV4 ( ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 4 */ +#define LL_ADC_CLOCK_SYNC_PCLK_DIV6 (ADC_CCR_ADCPRE_1 ) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 6 */ +#define LL_ADC_CLOCK_SYNC_PCLK_DIV8 (ADC_CCR_ADCPRE_1 | ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 8 */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_COMMON_PATH_INTERNAL ADC common - Measurement path to internal channels + * @{ + */ +/* Note: Other measurement paths to internal channels may be available */ +/* (connections to other peripherals). */ +/* If they are not listed below, they do not require any specific */ +/* path enable. In this case, Access to measurement path is done */ +/* only by selecting the corresponding ADC internal channel. */ +#define LL_ADC_PATH_INTERNAL_NONE 0x00000000UL /*!< ADC measurement paths all disabled */ +#define LL_ADC_PATH_INTERNAL_VREFINT (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel VrefInt */ +#define LL_ADC_PATH_INTERNAL_TEMPSENSOR (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel temperature sensor */ +#define LL_ADC_PATH_INTERNAL_VBAT (ADC_CCR_VBATE) /*!< ADC measurement path to internal channel Vbat */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_RESOLUTION ADC instance - Resolution + * @{ + */ +#define LL_ADC_RESOLUTION_12B 0x00000000UL /*!< ADC resolution 12 bits */ +#define LL_ADC_RESOLUTION_10B ( ADC_CR1_RES_0) /*!< ADC resolution 10 bits */ +#define LL_ADC_RESOLUTION_8B (ADC_CR1_RES_1 ) /*!< ADC resolution 8 bits */ +#define LL_ADC_RESOLUTION_6B (ADC_CR1_RES_1 | ADC_CR1_RES_0) /*!< ADC resolution 6 bits */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_DATA_ALIGN ADC instance - Data alignment + * @{ + */ +#define LL_ADC_DATA_ALIGN_RIGHT 0x00000000UL /*!< ADC conversion data alignment: right aligned (alignment on data register LSB bit 0)*/ +#define LL_ADC_DATA_ALIGN_LEFT (ADC_CR2_ALIGN) /*!< ADC conversion data alignment: left aligned (alignment on data register MSB bit 15)*/ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_SCAN_SELECTION ADC instance - Scan selection + * @{ + */ +#define LL_ADC_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC conversion is performed in unitary conversion mode (one channel converted, that defined in rank 1). Configuration of both groups regular and injected sequencers (sequence length, ...) is discarded: equivalent to length of 1 rank.*/ +#define LL_ADC_SEQ_SCAN_ENABLE (ADC_CR1_SCAN) /*!< ADC conversions are performed in sequence conversions mode, according to configuration of both groups regular and injected sequencers (sequence length, ...). */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_GROUPS ADC instance - Groups + * @{ + */ +#define LL_ADC_GROUP_REGULAR 0x00000001UL /*!< ADC group regular (available on all STM32 devices) */ +#define LL_ADC_GROUP_INJECTED 0x00000002UL /*!< ADC group injected (not available on all STM32 devices)*/ +#define LL_ADC_GROUP_REGULAR_INJECTED 0x00000003UL /*!< ADC both groups regular and injected */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_CHANNEL ADC instance - Channel number + * @{ + */ +#define LL_ADC_CHANNEL_0 (ADC_CHANNEL_0_NUMBER | ADC_CHANNEL_0_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN0 */ +#define LL_ADC_CHANNEL_1 (ADC_CHANNEL_1_NUMBER | ADC_CHANNEL_1_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN1 */ +#define LL_ADC_CHANNEL_2 (ADC_CHANNEL_2_NUMBER | ADC_CHANNEL_2_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN2 */ +#define LL_ADC_CHANNEL_3 (ADC_CHANNEL_3_NUMBER | ADC_CHANNEL_3_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN3 */ +#define LL_ADC_CHANNEL_4 (ADC_CHANNEL_4_NUMBER | ADC_CHANNEL_4_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN4 */ +#define LL_ADC_CHANNEL_5 (ADC_CHANNEL_5_NUMBER | ADC_CHANNEL_5_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN5 */ +#define LL_ADC_CHANNEL_6 (ADC_CHANNEL_6_NUMBER | ADC_CHANNEL_6_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN6 */ +#define LL_ADC_CHANNEL_7 (ADC_CHANNEL_7_NUMBER | ADC_CHANNEL_7_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN7 */ +#define LL_ADC_CHANNEL_8 (ADC_CHANNEL_8_NUMBER | ADC_CHANNEL_8_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN8 */ +#define LL_ADC_CHANNEL_9 (ADC_CHANNEL_9_NUMBER | ADC_CHANNEL_9_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN9 */ +#define LL_ADC_CHANNEL_10 (ADC_CHANNEL_10_NUMBER | ADC_CHANNEL_10_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN10 */ +#define LL_ADC_CHANNEL_11 (ADC_CHANNEL_11_NUMBER | ADC_CHANNEL_11_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN11 */ +#define LL_ADC_CHANNEL_12 (ADC_CHANNEL_12_NUMBER | ADC_CHANNEL_12_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN12 */ +#define LL_ADC_CHANNEL_13 (ADC_CHANNEL_13_NUMBER | ADC_CHANNEL_13_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN13 */ +#define LL_ADC_CHANNEL_14 (ADC_CHANNEL_14_NUMBER | ADC_CHANNEL_14_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN14 */ +#define LL_ADC_CHANNEL_15 (ADC_CHANNEL_15_NUMBER | ADC_CHANNEL_15_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN15 */ +#define LL_ADC_CHANNEL_16 (ADC_CHANNEL_16_NUMBER | ADC_CHANNEL_16_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN16 */ +#define LL_ADC_CHANNEL_17 (ADC_CHANNEL_17_NUMBER | ADC_CHANNEL_17_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN17 */ +#define LL_ADC_CHANNEL_18 (ADC_CHANNEL_18_NUMBER | ADC_CHANNEL_18_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN18 */ +#define LL_ADC_CHANNEL_VREFINT (LL_ADC_CHANNEL_17 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to VrefInt: Internal voltage reference. On STM32F4, ADC channel available only on ADC instance: ADC1. */ +#define LL_ADC_CHANNEL_VBAT (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda. On STM32F4, ADC channel available only on ADC instance: ADC1. */ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) +#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_16 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ +#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ +#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_TRIGGER_SOURCE ADC group regular - Trigger source + * @{ + */ +#define LL_ADC_REG_TRIG_SOFTWARE 0x00000000UL /*!< ADC group regular conversion trigger internal: SW start. */ +#define LL_ADC_REG_TRIG_EXT_TIM1_CH1 (ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM1_CH2 (ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM1_CH3 (ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM2_CH2 (ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM2_CH3 (ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM2_CH4 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM2_TRGO (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM3_CH1 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM3_TRGO (ADC_CR2_EXTSEL_3 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM4_CH4 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM4 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM5_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM5_CH2 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM5_CH3 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM8_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_TIM8_TRGO (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: external interrupt line 11. Trigger edge set to rising edge (default setting). */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_TRIGGER_EDGE ADC group regular - Trigger edge + * @{ + */ +#define LL_ADC_REG_TRIG_EXT_RISING ( ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to rising edge */ +#define LL_ADC_REG_TRIG_EXT_FALLING (ADC_CR2_EXTEN_1 ) /*!< ADC group regular conversion trigger polarity set to falling edge */ +#define LL_ADC_REG_TRIG_EXT_RISINGFALLING (ADC_CR2_EXTEN_1 | ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to both rising and falling edges */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_CONTINUOUS_MODE ADC group regular - Continuous mode +* @{ +*/ +#define LL_ADC_REG_CONV_SINGLE 0x00000000UL /*!< ADC conversions are performed in single mode: one conversion per trigger */ +#define LL_ADC_REG_CONV_CONTINUOUS (ADC_CR2_CONT) /*!< ADC conversions are performed in continuous mode: after the first trigger, following conversions launched successively automatically */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_DMA_TRANSFER ADC group regular - DMA transfer of ADC conversion data + * @{ + */ +#define LL_ADC_REG_DMA_TRANSFER_NONE 0x00000000UL /*!< ADC conversions are not transferred by DMA */ +#define LL_ADC_REG_DMA_TRANSFER_LIMITED ( ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. */ +#define LL_ADC_REG_DMA_TRANSFER_UNLIMITED (ADC_CR2_DDS | ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions). This ADC mode is intended to be used with DMA mode circular. */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_FLAG_EOC_SELECTION ADC group regular - Flag EOC selection (unitary or sequence conversions) + * @{ + */ +#define LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV 0x00000000UL /*!< ADC flag EOC (end of unitary conversion) selected */ +#define LL_ADC_REG_FLAG_EOC_UNITARY_CONV (ADC_CR2_EOCS) /*!< ADC flag EOS (end of sequence conversions) selected */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_SEQ_SCAN_LENGTH ADC group regular - Sequencer scan length + * @{ + */ +#define LL_ADC_REG_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group regular sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS ( ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 2 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS ( ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 3 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS ( ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 4 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS ( ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 5 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 6 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 7 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 8 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS (ADC_SQR1_L_3 ) /*!< ADC group regular sequencer enable with 9 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 10 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 11 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 12 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 13 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 14 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 15 ranks in the sequence */ +#define LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 16 ranks in the sequence */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_SEQ_DISCONT_MODE ADC group regular - Sequencer discontinuous mode + * @{ + */ +#define LL_ADC_REG_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group regular sequencer discontinuous mode disable */ +#define LL_ADC_REG_SEQ_DISCONT_1RANK ( ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every rank */ +#define LL_ADC_REG_SEQ_DISCONT_2RANKS ( ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enabled with sequence interruption every 2 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_3RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 3 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_4RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 4 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_5RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 5 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_6RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 6 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_7RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 7 ranks */ +#define LL_ADC_REG_SEQ_DISCONT_8RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 8 ranks */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_REG_SEQ_RANKS ADC group regular - Sequencer ranks + * @{ + */ +#define LL_ADC_REG_RANK_1 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_1_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 1 */ +#define LL_ADC_REG_RANK_2 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_2_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 2 */ +#define LL_ADC_REG_RANK_3 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_3_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 3 */ +#define LL_ADC_REG_RANK_4 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_4_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 4 */ +#define LL_ADC_REG_RANK_5 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_5_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 5 */ +#define LL_ADC_REG_RANK_6 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_6_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 6 */ +#define LL_ADC_REG_RANK_7 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_7_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 7 */ +#define LL_ADC_REG_RANK_8 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_8_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 8 */ +#define LL_ADC_REG_RANK_9 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_9_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 9 */ +#define LL_ADC_REG_RANK_10 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_10_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 10 */ +#define LL_ADC_REG_RANK_11 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_11_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 11 */ +#define LL_ADC_REG_RANK_12 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_12_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 12 */ +#define LL_ADC_REG_RANK_13 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_13_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 13 */ +#define LL_ADC_REG_RANK_14 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_14_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 14 */ +#define LL_ADC_REG_RANK_15 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_15_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 15 */ +#define LL_ADC_REG_RANK_16 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_16_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 16 */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_INJ_TRIGGER_SOURCE ADC group injected - Trigger source + * @{ + */ +#define LL_ADC_INJ_TRIG_SOFTWARE 0x00000000UL /*!< ADC group injected conversion trigger internal: SW start. */ +#define LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM1_TRGO (ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM3_CH2 (ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM4_CH1 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM4_CH2 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (ADC_CR2_JEXTSEL_3 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 TRGO. Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM8_CH3 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ +#define LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: external interrupt line 15. Trigger edge set to rising edge (default setting). */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_INJ_TRIGGER_EDGE ADC group injected - Trigger edge + * @{ + */ +#define LL_ADC_INJ_TRIG_EXT_RISING ( ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to rising edge */ +#define LL_ADC_INJ_TRIG_EXT_FALLING (ADC_CR2_JEXTEN_1 ) /*!< ADC group injected conversion trigger polarity set to falling edge */ +#define LL_ADC_INJ_TRIG_EXT_RISINGFALLING (ADC_CR2_JEXTEN_1 | ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to both rising and falling edges */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_INJ_TRIG_AUTO ADC group injected - Automatic trigger mode +* @{ +*/ +#define LL_ADC_INJ_TRIG_INDEPENDENT 0x00000000UL /*!< ADC group injected conversion trigger independent. Setting mandatory if ADC group injected injected trigger source is set to an external trigger. */ +#define LL_ADC_INJ_TRIG_FROM_GRP_REGULAR (ADC_CR1_JAUTO) /*!< ADC group injected conversion trigger from ADC group regular. Setting compliant only with group injected trigger source set to SW start, without any further action on ADC group injected conversion start or stop: in this case, ADC group injected is controlled only from ADC group regular. */ +/** + * @} + */ + + +/** @defgroup ADC_LL_EC_INJ_SEQ_SCAN_LENGTH ADC group injected - Sequencer scan length + * @{ + */ +#define LL_ADC_INJ_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group injected sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ +#define LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS ( ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 2 ranks in the sequence */ +#define LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS (ADC_JSQR_JL_1 ) /*!< ADC group injected sequencer enable with 3 ranks in the sequence */ +#define LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS (ADC_JSQR_JL_1 | ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 4 ranks in the sequence */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_INJ_SEQ_DISCONT_MODE ADC group injected - Sequencer discontinuous mode + * @{ + */ +#define LL_ADC_INJ_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group injected sequencer discontinuous mode disable */ +#define LL_ADC_INJ_SEQ_DISCONT_1RANK (ADC_CR1_JDISCEN) /*!< ADC group injected sequencer discontinuous mode enable with sequence interruption every rank */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_INJ_SEQ_RANKS ADC group injected - Sequencer ranks + * @{ + */ +#define LL_ADC_INJ_RANK_1 (ADC_JDR1_REGOFFSET | ADC_JOFR1_REGOFFSET | 0x00000001UL) /*!< ADC group injected sequencer rank 1 */ +#define LL_ADC_INJ_RANK_2 (ADC_JDR2_REGOFFSET | ADC_JOFR2_REGOFFSET | 0x00000002UL) /*!< ADC group injected sequencer rank 2 */ +#define LL_ADC_INJ_RANK_3 (ADC_JDR3_REGOFFSET | ADC_JOFR3_REGOFFSET | 0x00000003UL) /*!< ADC group injected sequencer rank 3 */ +#define LL_ADC_INJ_RANK_4 (ADC_JDR4_REGOFFSET | ADC_JOFR4_REGOFFSET | 0x00000004UL) /*!< ADC group injected sequencer rank 4 */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_CHANNEL_SAMPLINGTIME Channel - Sampling time + * @{ + */ +#define LL_ADC_SAMPLINGTIME_3CYCLES 0x00000000UL /*!< Sampling time 3 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_15CYCLES (ADC_SMPR1_SMP10_0) /*!< Sampling time 15 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_28CYCLES (ADC_SMPR1_SMP10_1) /*!< Sampling time 28 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_56CYCLES (ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0) /*!< Sampling time 56 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_84CYCLES (ADC_SMPR1_SMP10_2) /*!< Sampling time 84 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_112CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0) /*!< Sampling time 112 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_144CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1) /*!< Sampling time 144 ADC clock cycles */ +#define LL_ADC_SAMPLINGTIME_480CYCLES (ADC_SMPR1_SMP10) /*!< Sampling time 480 ADC clock cycles */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_AWD_NUMBER Analog watchdog - Analog watchdog number + * @{ + */ +#define LL_ADC_AWD1 (ADC_AWD_CR1_CHANNEL_MASK | ADC_AWD_CR1_REGOFFSET) /*!< ADC analog watchdog number 1 */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_AWD_CHANNELS Analog watchdog - Monitored channels + * @{ + */ +#define LL_ADC_AWD_DISABLE 0x00000000UL /*!< ADC analog watchdog monitoring disabled */ +#define LL_ADC_AWD_ALL_CHANNELS_REG ( ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group regular only */ +#define LL_ADC_AWD_ALL_CHANNELS_INJ ( ADC_CR1_JAWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group injected only */ +#define LL_ADC_AWD_ALL_CHANNELS_REG_INJ ( ADC_CR1_JAWDEN | ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_0_REG ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_0_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_0_REG_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_1_REG ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_1_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_1_REG_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_2_REG ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_2_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_2_REG_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_3_REG ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_3_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_3_REG_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_4_REG ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_4_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_4_REG_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_5_REG ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_5_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_5_REG_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_6_REG ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_6_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_6_REG_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_7_REG ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_7_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_7_REG_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_8_REG ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_8_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_8_REG_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_9_REG ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_9_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_9_REG_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_10_REG ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_10_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_10_REG_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_11_REG ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_11_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_11_REG_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_12_REG ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_12_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_12_REG_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_13_REG ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_13_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_13_REG_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_14_REG ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_14_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_14_REG_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_15_REG ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_15_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_15_REG_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_16_REG ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_16_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_16_REG_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_17_REG ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_17_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_17_REG_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by either group regular or injected */ +#define LL_ADC_AWD_CHANNEL_18_REG ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group regular only */ +#define LL_ADC_AWD_CHANNEL_18_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group injected only */ +#define LL_ADC_AWD_CHANNEL_18_REG_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by either group regular or injected */ +#define LL_ADC_AWD_CH_VREFINT_REG ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group regular only */ +#define LL_ADC_AWD_CH_VREFINT_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group injected only */ +#define LL_ADC_AWD_CH_VREFINT_REG_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by either group regular or injected */ +#define LL_ADC_AWD_CH_VBAT_REG ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group regular only */ +#define LL_ADC_AWD_CH_VBAT_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group injected only */ +#define LL_ADC_AWD_CH_VBAT_REG_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda */ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) +#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only */ +#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only */ +#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ +#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ +#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ +#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ +#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_AWD_THRESHOLDS Analog watchdog - Thresholds + * @{ + */ +#define LL_ADC_AWD_THRESHOLD_HIGH (ADC_AWD_TR1_HIGH_REGOFFSET) /*!< ADC analog watchdog threshold high */ +#define LL_ADC_AWD_THRESHOLD_LOW (ADC_AWD_TR1_LOW_REGOFFSET) /*!< ADC analog watchdog threshold low */ +/** + * @} + */ + +#if defined(ADC_MULTIMODE_SUPPORT) +/** @defgroup ADC_LL_EC_MULTI_MODE Multimode - Mode + * @{ + */ +#define LL_ADC_MULTI_INDEPENDENT 0x00000000UL /*!< ADC dual mode disabled (ADC independent mode) */ +#define LL_ADC_MULTI_DUAL_REG_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: group regular simultaneous */ +#define LL_ADC_MULTI_DUAL_REG_INTERL ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved */ +#define LL_ADC_MULTI_DUAL_INJ_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected simultaneous */ +#define LL_ADC_MULTI_DUAL_INJ_ALTERN (ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ +#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM ( ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected simultaneous */ +#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT ( ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected alternate trigger */ +#define LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM ( ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved + group injected simultaneous */ +#if defined(ADC3) +#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected simultaneous */ +#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected alternate trigger */ +#define LL_ADC_MULTI_TRIPLE_INJ_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected simultaneous */ +#define LL_ADC_MULTI_TRIPLE_REG_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: group regular simultaneous */ +#define LL_ADC_MULTI_TRIPLE_REG_INTERL (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular interleaved */ +#define LL_ADC_MULTI_TRIPLE_INJ_ALTERN (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ +#endif +/** + * @} + */ + +/** @defgroup ADC_LL_EC_MULTI_DMA_TRANSFER Multimode - DMA transfer + * @{ + */ +#define LL_ADC_MULTI_REG_DMA_EACH_ADC 0x00000000UL /*!< ADC multimode group regular conversions are transferred by DMA: each ADC uses its own DMA channel, with its individual DMA transfer settings */ +#define LL_ADC_MULTI_REG_DMA_LIMIT_1 ( ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ +#define LL_ADC_MULTI_REG_DMA_LIMIT_2 ( ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words one by one, ADC2&1 then ADC1&3 then ADC3&2. */ +#define LL_ADC_MULTI_REG_DMA_LIMIT_3 ( ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ +#define LL_ADC_MULTI_REG_DMA_UNLMT_1 (ADC_CCR_DDS | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ +#define LL_ADC_MULTI_REG_DMA_UNLMT_2 (ADC_CCR_DDS | ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words by pairs, ADC2&1 then ADC1&3 then ADC3&2. */ +#define LL_ADC_MULTI_REG_DMA_UNLMT_3 (ADC_CCR_DDS | ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_MULTI_TWOSMP_DELAY Multimode - Delay between two sampling phases + * @{ + */ +#define LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES 0x00000000UL /*!< ADC multimode delay between two sampling phases: 5 ADC clock cycles*/ +#define LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES ( ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 6 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES ( ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 7 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES ( ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 8 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES ( ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 9 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 10 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 11 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 12 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES (ADC_CCR_DELAY_3 ) /*!< ADC multimode delay between two sampling phases: 13 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 14 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 15 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 16 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 17 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 18 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 19 ADC clock cycles */ +#define LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 20 ADC clock cycles */ +/** + * @} + */ + +/** @defgroup ADC_LL_EC_MULTI_MASTER_SLAVE Multimode - ADC master or slave + * @{ + */ +#define LL_ADC_MULTI_MASTER ( ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: ADC master */ +#define LL_ADC_MULTI_SLAVE (ADC_CDR_RDATA_SLV ) /*!< In multimode, selection among several ADC instances: ADC slave */ +#define LL_ADC_MULTI_MASTER_SLAVE (ADC_CDR_RDATA_SLV | ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: both ADC master and ADC slave */ +/** + * @} + */ + +#endif /* ADC_MULTIMODE_SUPPORT */ + + +/** @defgroup ADC_LL_EC_HW_DELAYS Definitions of ADC hardware constraints delays + * @note Only ADC IP HW delays are defined in ADC LL driver driver, + * not timeout values. + * For details on delays values, refer to descriptions in source code + * above each literal definition. + * @{ + */ + +/* Note: Only ADC IP HW delays are defined in ADC LL driver driver, */ +/* not timeout values. */ +/* Timeout values for ADC operations are dependent to device clock */ +/* configuration (system clock versus ADC clock), */ +/* and therefore must be defined in user application. */ +/* Indications for estimation of ADC timeout delays, for this */ +/* STM32 series: */ +/* - ADC enable time: maximum delay is 2us */ +/* (refer to device datasheet, parameter "tSTAB") */ +/* - ADC conversion time: duration depending on ADC clock and ADC */ +/* configuration. */ +/* (refer to device reference manual, section "Timing") */ + +/* Delay for internal voltage reference stabilization time. */ +/* Delay set to maximum value (refer to device datasheet, */ +/* parameter "tSTART"). */ +/* Unit: us */ +#define LL_ADC_DELAY_VREFINT_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ + +/* Delay for temperature sensor stabilization time. */ +/* Literal set to maximum value (refer to device datasheet, */ +/* parameter "tSTART"). */ +/* Unit: us */ +#define LL_ADC_DELAY_TEMPSENSOR_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ + +/** + * @} + */ + +/** + * @} + */ + + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup ADC_LL_Exported_Macros ADC Exported Macros + * @{ + */ + +/** @defgroup ADC_LL_EM_WRITE_READ Common write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in ADC register + * @param __INSTANCE__ ADC Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_ADC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in ADC register + * @param __INSTANCE__ ADC Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_ADC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** @defgroup ADC_LL_EM_HELPER_MACRO ADC helper macro + * @{ + */ + +/** + * @brief Helper macro to get ADC channel number in decimal format + * from literals LL_ADC_CHANNEL_x. + * @note Example: + * __LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_CHANNEL_4) + * will return decimal number "4". + * @note The input can be a value from functions where a channel + * number is returned, either defined with number + * or with bitfield (only one bit must be set). + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval Value between Min_Data=0 and Max_Data=18 + */ +#define __LL_ADC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \ + (((__CHANNEL__) & ADC_CHANNEL_ID_NUMBER_MASK) >> ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) + +/** + * @brief Helper macro to get ADC channel in literal format LL_ADC_CHANNEL_x + * from number in decimal format. + * @note Example: + * __LL_ADC_DECIMAL_NB_TO_CHANNEL(4) + * will return a data equivalent to "LL_ADC_CHANNEL_4". + * @param __DECIMAL_NB__ Value between Min_Data=0 and Max_Data=18 + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n + * (1) For ADC channel read back from ADC register, + * comparison with internal channel parameter to be done + * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). + */ +#define __LL_ADC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ + (((__DECIMAL_NB__) <= 9UL) \ + ? ( \ + ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ + (ADC_SMPR2_REGOFFSET | (((uint32_t) (3UL * (__DECIMAL_NB__))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ + ) \ + : \ + ( \ + ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ + (ADC_SMPR1_REGOFFSET | (((uint32_t) (3UL * ((__DECIMAL_NB__) - 10UL))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ + ) \ + ) + +/** + * @brief Helper macro to determine whether the selected channel + * corresponds to literal definitions of driver. + * @note The different literal definitions of ADC channels are: + * - ADC internal channel: + * LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ... + * - ADC external channel (channel connected to a GPIO pin): + * LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ... + * @note The channel parameter must be a value defined from literal + * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, + * LL_ADC_CHANNEL_TEMPSENSOR, ...), + * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...), + * must not be a value from functions where a channel number is + * returned from ADC registers, + * because internal and external channels share the same channel + * number in ADC registers. The differentiation is made only with + * parameters definitions of driver. + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval Value "0" if the channel corresponds to a parameter definition of a ADC external channel (channel connected to a GPIO pin). + * Value "1" if the channel corresponds to a parameter definition of a ADC internal channel. + */ +#define __LL_ADC_IS_CHANNEL_INTERNAL(__CHANNEL__) \ + (((__CHANNEL__) & ADC_CHANNEL_ID_INTERNAL_CH_MASK) != 0UL) + +/** + * @brief Helper macro to convert a channel defined from parameter + * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, + * LL_ADC_CHANNEL_TEMPSENSOR, ...), + * to its equivalent parameter definition of a ADC external channel + * (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...). + * @note The channel parameter can be, additionally to a value + * defined from parameter definition of a ADC internal channel + * (LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ...), + * a value defined from parameter definition of + * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) + * or a value from functions where a channel number is returned + * from ADC registers. + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + */ +#define __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(__CHANNEL__) \ + ((__CHANNEL__) & ~ADC_CHANNEL_ID_INTERNAL_CH_MASK) + +/** + * @brief Helper macro to determine whether the internal channel + * selected is available on the ADC instance selected. + * @note The channel parameter must be a value defined from parameter + * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, + * LL_ADC_CHANNEL_TEMPSENSOR, ...), + * must not be a value defined from parameter definition of + * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) + * or a value from functions where a channel number is + * returned from ADC registers, + * because internal and external channels share the same channel + * number in ADC registers. The differentiation is made only with + * parameters definitions of driver. + * @param __ADC_INSTANCE__ ADC instance + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1. + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval Value "0" if the internal channel selected is not available on the ADC instance selected. + * Value "1" if the internal channel selected is available on the ADC instance selected. + */ +#define __LL_ADC_IS_CHANNEL_INTERNAL_AVAILABLE(__ADC_INSTANCE__, __CHANNEL__) \ + ( \ + ((__CHANNEL__) == LL_ADC_CHANNEL_VREFINT) || \ + ((__CHANNEL__) == LL_ADC_CHANNEL_TEMPSENSOR) || \ + ((__CHANNEL__) == LL_ADC_CHANNEL_VBAT) \ + ) +/** + * @brief Helper macro to define ADC analog watchdog parameter: + * define a single channel to monitor with analog watchdog + * from sequencer channel and groups definition. + * @note To be used with function @ref LL_ADC_SetAnalogWDMonitChannels(). + * Example: + * LL_ADC_SetAnalogWDMonitChannels( + * ADC1, LL_ADC_AWD1, + * __LL_ADC_ANALOGWD_CHANNEL_GROUP(LL_ADC_CHANNEL4, LL_ADC_GROUP_REGULAR)) + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n + * (1) For ADC channel read back from ADC register, + * comparison with internal channel parameter to be done + * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). + * @param __GROUP__ This parameter can be one of the following values: + * @arg @ref LL_ADC_GROUP_REGULAR + * @arg @ref LL_ADC_GROUP_INJECTED + * @arg @ref LL_ADC_GROUP_REGULAR_INJECTED + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_AWD_DISABLE + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG + * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG + * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG + * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG + * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG + * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG + * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG + * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG + * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG + * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG + * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG + * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG + * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG + * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG + * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG + * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG + * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG + * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG + * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG + * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ + * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) + * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) + * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) + * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) + * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) + * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + */ +#define __LL_ADC_ANALOGWD_CHANNEL_GROUP(__CHANNEL__, __GROUP__) \ + (((__GROUP__) == LL_ADC_GROUP_REGULAR) \ + ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ + : \ + ((__GROUP__) == LL_ADC_GROUP_INJECTED) \ + ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) \ + : \ + (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ + ) + +/** + * @brief Helper macro to set the value of ADC analog watchdog threshold high + * or low in function of ADC resolution, when ADC resolution is + * different of 12 bits. + * @note To be used with function @ref LL_ADC_SetAnalogWDThresholds(). + * Example, with a ADC resolution of 8 bits, to set the value of + * analog watchdog threshold high (on 8 bits): + * LL_ADC_SetAnalogWDThresholds + * (< ADCx param >, + * __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(LL_ADC_RESOLUTION_8B, ) + * ); + * @param __ADC_RESOLUTION__ This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @param __AWD_THRESHOLD__ Value between Min_Data=0x000 and Max_Data=0xFFF + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +#define __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD__) \ + ((__AWD_THRESHOLD__) << ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) + +/** + * @brief Helper macro to get the value of ADC analog watchdog threshold high + * or low in function of ADC resolution, when ADC resolution is + * different of 12 bits. + * @note To be used with function @ref LL_ADC_GetAnalogWDThresholds(). + * Example, with a ADC resolution of 8 bits, to get the value of + * analog watchdog threshold high (on 8 bits): + * < threshold_value_6_bits > = __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION + * (LL_ADC_RESOLUTION_8B, + * LL_ADC_GetAnalogWDThresholds(, LL_ADC_AWD_THRESHOLD_HIGH) + * ); + * @param __ADC_RESOLUTION__ This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @param __AWD_THRESHOLD_12_BITS__ Value between Min_Data=0x000 and Max_Data=0xFFF + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +#define __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD_12_BITS__) \ + ((__AWD_THRESHOLD_12_BITS__) >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) + +#if defined(ADC_MULTIMODE_SUPPORT) +/** + * @brief Helper macro to get the ADC multimode conversion data of ADC master + * or ADC slave from raw value with both ADC conversion data concatenated. + * @note This macro is intended to be used when multimode transfer by DMA + * is enabled: refer to function @ref LL_ADC_SetMultiDMATransfer(). + * In this case the transferred data need to processed with this macro + * to separate the conversion data of ADC master and ADC slave. + * @param __ADC_MULTI_MASTER_SLAVE__ This parameter can be one of the following values: + * @arg @ref LL_ADC_MULTI_MASTER + * @arg @ref LL_ADC_MULTI_SLAVE + * @param __ADC_MULTI_CONV_DATA__ Value between Min_Data=0x000 and Max_Data=0xFFF + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +#define __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(__ADC_MULTI_MASTER_SLAVE__, __ADC_MULTI_CONV_DATA__) \ + (((__ADC_MULTI_CONV_DATA__) >> POSITION_VAL((__ADC_MULTI_MASTER_SLAVE__))) & ADC_CDR_RDATA_MST) +#endif + +/** + * @brief Helper macro to select the ADC common instance + * to which is belonging the selected ADC instance. + * @note ADC common register instance can be used for: + * - Set parameters common to several ADC instances + * - Multimode (for devices with several ADC instances) + * Refer to functions having argument "ADCxy_COMMON" as parameter. + * @param __ADCx__ ADC instance + * @retval ADC common register instance + */ +#if defined(ADC1) && defined(ADC2) && defined(ADC3) +#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ + (ADC123_COMMON) +#elif defined(ADC1) && defined(ADC2) +#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ + (ADC12_COMMON) +#else +#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ + (ADC1_COMMON) +#endif + +/** + * @brief Helper macro to check if all ADC instances sharing the same + * ADC common instance are disabled. + * @note This check is required by functions with setting conditioned to + * ADC state: + * All ADC instances of the ADC common group must be disabled. + * Refer to functions having argument "ADCxy_COMMON" as parameter. + * @note On devices with only 1 ADC common instance, parameter of this macro + * is useless and can be ignored (parameter kept for compatibility + * with devices featuring several ADC common instances). + * @param __ADCXY_COMMON__ ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Value "0" if all ADC instances sharing the same ADC common instance + * are disabled. + * Value "1" if at least one ADC instance sharing the same ADC common instance + * is enabled. + */ +#if defined(ADC1) && defined(ADC2) && defined(ADC3) +#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ + (LL_ADC_IsEnabled(ADC1) | \ + LL_ADC_IsEnabled(ADC2) | \ + LL_ADC_IsEnabled(ADC3) ) +#elif defined(ADC1) && defined(ADC2) +#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ + (LL_ADC_IsEnabled(ADC1) | \ + LL_ADC_IsEnabled(ADC2) ) +#else +#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ + (LL_ADC_IsEnabled(ADC1)) +#endif + +/** + * @brief Helper macro to define the ADC conversion data full-scale digital + * value corresponding to the selected ADC resolution. + * @note ADC conversion data full-scale corresponds to voltage range + * determined by analog voltage references Vref+ and Vref- + * (refer to reference manual). + * @param __ADC_RESOLUTION__ This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval ADC conversion data equivalent voltage value (unit: mVolt) + */ +#define __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ + (0xFFFU >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) + +/** + * @brief Helper macro to convert the ADC conversion data from + * a resolution to another resolution. + * @param __DATA__ ADC conversion data to be converted + * @param __ADC_RESOLUTION_CURRENT__ Resolution of to the data to be converted + * This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @param __ADC_RESOLUTION_TARGET__ Resolution of the data after conversion + * This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval ADC conversion data to the requested resolution + */ +#define __LL_ADC_CONVERT_DATA_RESOLUTION(__DATA__, __ADC_RESOLUTION_CURRENT__, __ADC_RESOLUTION_TARGET__) \ + (((__DATA__) \ + << ((__ADC_RESOLUTION_CURRENT__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) \ + >> ((__ADC_RESOLUTION_TARGET__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL)) \ + ) + +/** + * @brief Helper macro to calculate the voltage (unit: mVolt) + * corresponding to a ADC conversion data (unit: digital value). + * @note Analog reference voltage (Vref+) must be either known from + * user board environment or can be calculated using ADC measurement + * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). + * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) + * @param __ADC_DATA__ ADC conversion data (resolution 12 bits) + * (unit: digital value). + * @param __ADC_RESOLUTION__ This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval ADC conversion data equivalent voltage value (unit: mVolt) + */ +#define __LL_ADC_CALC_DATA_TO_VOLTAGE(__VREFANALOG_VOLTAGE__,\ + __ADC_DATA__,\ + __ADC_RESOLUTION__) \ + ((__ADC_DATA__) * (__VREFANALOG_VOLTAGE__) \ + / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ + ) + +/** + * @brief Helper macro to calculate analog reference voltage (Vref+) + * (unit: mVolt) from ADC conversion data of internal voltage + * reference VrefInt. + * @note Computation is using VrefInt calibration value + * stored in system memory for each device during production. + * @note This voltage depends on user board environment: voltage level + * connected to pin Vref+. + * On devices with small package, the pin Vref+ is not present + * and internally bonded to pin Vdda. + * @note On this STM32 series, calibration data of internal voltage reference + * VrefInt corresponds to a resolution of 12 bits, + * this is the recommended ADC resolution to convert voltage of + * internal voltage reference VrefInt. + * Otherwise, this macro performs the processing to scale + * ADC conversion data to 12 bits. + * @param __VREFINT_ADC_DATA__ ADC conversion data (resolution 12 bits) + * of internal voltage reference VrefInt (unit: digital value). + * @param __ADC_RESOLUTION__ This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval Analog reference voltage (unit: mV) + */ +#define __LL_ADC_CALC_VREFANALOG_VOLTAGE(__VREFINT_ADC_DATA__,\ + __ADC_RESOLUTION__) \ + (((uint32_t)(*VREFINT_CAL_ADDR) * VREFINT_CAL_VREF) \ + / __LL_ADC_CONVERT_DATA_RESOLUTION((__VREFINT_ADC_DATA__), \ + (__ADC_RESOLUTION__), \ + LL_ADC_RESOLUTION_12B)) + +/* Note: On device STM32F4x9, calibration parameter TS_CAL2 is not available. */ +/* Therefore, helper macro __LL_ADC_CALC_TEMPERATURE() is not available.*/ +/* Use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). */ +#if !defined(STM32F469) && !defined(STM32F479xx) && !defined(STM32F429xx) && !defined(STM32F439xx) +/** + * @brief Helper macro to calculate the temperature (unit: degree Celsius) + * from ADC conversion data of internal temperature sensor. + * @note Computation is using temperature sensor calibration values + * stored in system memory for each device during production. + * @note Calculation formula: + * Temperature = ((TS_ADC_DATA - TS_CAL1) + * * (TS_CAL2_TEMP - TS_CAL1_TEMP)) + * / (TS_CAL2 - TS_CAL1) + TS_CAL1_TEMP + * with TS_ADC_DATA = temperature sensor raw data measured by ADC + * Avg_Slope = (TS_CAL2 - TS_CAL1) + * / (TS_CAL2_TEMP - TS_CAL1_TEMP) + * TS_CAL1 = equivalent TS_ADC_DATA at temperature + * TEMP_DEGC_CAL1 (calibrated in factory) + * TS_CAL2 = equivalent TS_ADC_DATA at temperature + * TEMP_DEGC_CAL2 (calibrated in factory) + * Caution: Calculation relevancy under reserve that calibration + * parameters are correct (address and data). + * To calculate temperature using temperature sensor + * datasheet typical values (generic values less, therefore + * less accurate than calibrated values), + * use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). + * @note As calculation input, the analog reference voltage (Vref+) must be + * defined as it impacts the ADC LSB equivalent voltage. + * @note Analog reference voltage (Vref+) must be either known from + * user board environment or can be calculated using ADC measurement + * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). + * @note On this STM32 series, calibration data of temperature sensor + * corresponds to a resolution of 12 bits, + * this is the recommended ADC resolution to convert voltage of + * temperature sensor. + * Otherwise, this macro performs the processing to scale + * ADC conversion data to 12 bits. + * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) + * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal + * temperature sensor (unit: digital value). + * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature + * sensor voltage has been measured. + * This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval Temperature (unit: degree Celsius) + */ +#define __LL_ADC_CALC_TEMPERATURE(__VREFANALOG_VOLTAGE__,\ + __TEMPSENSOR_ADC_DATA__,\ + __ADC_RESOLUTION__) \ + (((( ((int32_t)((__LL_ADC_CONVERT_DATA_RESOLUTION((__TEMPSENSOR_ADC_DATA__), \ + (__ADC_RESOLUTION__), \ + LL_ADC_RESOLUTION_12B) \ + * (__VREFANALOG_VOLTAGE__)) \ + / TEMPSENSOR_CAL_VREFANALOG) \ + - (int32_t) *TEMPSENSOR_CAL1_ADDR) \ + ) * (int32_t)(TEMPSENSOR_CAL2_TEMP - TEMPSENSOR_CAL1_TEMP) \ + ) / (int32_t)((int32_t)*TEMPSENSOR_CAL2_ADDR - (int32_t)*TEMPSENSOR_CAL1_ADDR) \ + ) + TEMPSENSOR_CAL1_TEMP \ + ) +#endif + +/** + * @brief Helper macro to calculate the temperature (unit: degree Celsius) + * from ADC conversion data of internal temperature sensor. + * @note Computation is using temperature sensor typical values + * (refer to device datasheet). + * @note Calculation formula: + * Temperature = (TS_TYP_CALx_VOLT(uV) - TS_ADC_DATA * Conversion_uV) + * / Avg_Slope + CALx_TEMP + * with TS_ADC_DATA = temperature sensor raw data measured by ADC + * (unit: digital value) + * Avg_Slope = temperature sensor slope + * (unit: uV/Degree Celsius) + * TS_TYP_CALx_VOLT = temperature sensor digital value at + * temperature CALx_TEMP (unit: mV) + * Caution: Calculation relevancy under reserve the temperature sensor + * of the current device has characteristics in line with + * datasheet typical values. + * If temperature sensor calibration values are available on + * on this device (presence of macro __LL_ADC_CALC_TEMPERATURE()), + * temperature calculation will be more accurate using + * helper macro @ref __LL_ADC_CALC_TEMPERATURE(). + * @note As calculation input, the analog reference voltage (Vref+) must be + * defined as it impacts the ADC LSB equivalent voltage. + * @note Analog reference voltage (Vref+) must be either known from + * user board environment or can be calculated using ADC measurement + * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). + * @note ADC measurement data must correspond to a resolution of 12bits + * (full scale digital value 4095). If not the case, the data must be + * preliminarily rescaled to an equivalent resolution of 12 bits. + * @param __TEMPSENSOR_TYP_AVGSLOPE__ Device datasheet data Temperature sensor slope typical value (unit uV/DegCelsius). + * On STM32F4, refer to device datasheet parameter "Avg_Slope". + * @param __TEMPSENSOR_TYP_CALX_V__ Device datasheet data Temperature sensor voltage typical value (at temperature and Vref+ defined in parameters below) (unit mV). + * On STM32F4, refer to device datasheet parameter "V25". + * @param __TEMPSENSOR_CALX_TEMP__ Device datasheet data Temperature at which temperature sensor voltage (see parameter above) is corresponding (unit mV) + * @param __VREFANALOG_VOLTAGE__ Analog voltage reference (Vref+) voltage (unit mV) + * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal temperature sensor (unit digital value). + * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature sensor voltage has been measured. + * This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval Temperature (unit: degree Celsius) + */ +#define __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(__TEMPSENSOR_TYP_AVGSLOPE__,\ + __TEMPSENSOR_TYP_CALX_V__,\ + __TEMPSENSOR_CALX_TEMP__,\ + __VREFANALOG_VOLTAGE__,\ + __TEMPSENSOR_ADC_DATA__,\ + __ADC_RESOLUTION__) \ + ((( ( \ + (int32_t)(((__TEMPSENSOR_TYP_CALX_V__)) \ + * 1000) \ + - \ + (int32_t)((((__TEMPSENSOR_ADC_DATA__) * (__VREFANALOG_VOLTAGE__)) \ + / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__)) \ + * 1000) \ + ) \ + ) / (__TEMPSENSOR_TYP_AVGSLOPE__) \ + ) + (__TEMPSENSOR_CALX_TEMP__) \ + ) + +/** + * @} + */ + +/** + * @} + */ + + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup ADC_LL_Exported_Functions ADC Exported Functions + * @{ + */ + +/** @defgroup ADC_LL_EF_DMA_Management ADC DMA management + * @{ + */ +/* Note: LL ADC functions to set DMA transfer are located into sections of */ +/* configuration of ADC instance, groups and multimode (if available): */ +/* @ref LL_ADC_REG_SetDMATransfer(), ... */ + +/** + * @brief Function to help to configure DMA transfer from ADC: retrieve the + * ADC register address from ADC instance and a list of ADC registers + * intended to be used (most commonly) with DMA transfer. + * @note These ADC registers are data registers: + * when ADC conversion data is available in ADC data registers, + * ADC generates a DMA transfer request. + * @note This macro is intended to be used with LL DMA driver, refer to + * function "LL_DMA_ConfigAddresses()". + * Example: + * LL_DMA_ConfigAddresses(DMA1, + * LL_DMA_CHANNEL_1, + * LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA), + * (uint32_t)&< array or variable >, + * LL_DMA_DIRECTION_PERIPH_TO_MEMORY); + * @note For devices with several ADC: in multimode, some devices + * use a different data register outside of ADC instance scope + * (common data register). This macro manages this register difference, + * only ADC instance has to be set as parameter. + * @rmtoll DR RDATA LL_ADC_DMA_GetRegAddr\n + * CDR RDATA_MST LL_ADC_DMA_GetRegAddr\n + * CDR RDATA_SLV LL_ADC_DMA_GetRegAddr + * @param ADCx ADC instance + * @param Register This parameter can be one of the following values: + * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA + * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA_MULTI (1) + * + * (1) Available on devices with several ADC instances. + * @retval ADC register address + */ +#if defined(ADC_MULTIMODE_SUPPORT) +__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) +{ + uint32_t data_reg_addr = 0UL; + + if (Register == LL_ADC_DMA_REG_REGULAR_DATA) + { + /* Retrieve address of register DR */ + data_reg_addr = (uint32_t)&(ADCx->DR); + } + else /* (Register == LL_ADC_DMA_REG_REGULAR_DATA_MULTI) */ + { + /* Retrieve address of register CDR */ + data_reg_addr = (uint32_t)&((__LL_ADC_COMMON_INSTANCE(ADCx))->CDR); + } + + return data_reg_addr; +} +#else +__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) +{ + /* Retrieve address of register DR */ + return (uint32_t)&(ADCx->DR); +} +#endif + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_Common Configuration of ADC hierarchical scope: common to several ADC instances + * @{ + */ + +/** + * @brief Set parameter common to several ADC: Clock source and prescaler. + * @rmtoll CCR ADCPRE LL_ADC_SetCommonClock + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param CommonClock This parameter can be one of the following values: + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t CommonClock) +{ + MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE, CommonClock); +} + +/** + * @brief Get parameter common to several ADC: Clock source and prescaler. + * @rmtoll CCR ADCPRE LL_ADC_GetCommonClock + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 + * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 + */ +__STATIC_INLINE uint32_t LL_ADC_GetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE)); +} + +/** + * @brief Set parameter common to several ADC: measurement path to internal + * channels (VrefInt, temperature sensor, ...). + * @note One or several values can be selected. + * Example: (LL_ADC_PATH_INTERNAL_VREFINT | + * LL_ADC_PATH_INTERNAL_TEMPSENSOR) + * @note Stabilization time of measurement path to internal channel: + * After enabling internal paths, before starting ADC conversion, + * a delay is required for internal voltage reference and + * temperature sensor stabilization time. + * Refer to device datasheet. + * Refer to literal @ref LL_ADC_DELAY_VREFINT_STAB_US. + * Refer to literal @ref LL_ADC_DELAY_TEMPSENSOR_STAB_US. + * @note ADC internal channel sampling time constraint: + * For ADC conversion of internal channels, + * a sampling time minimum value is required. + * Refer to device datasheet. + * @rmtoll CCR TSVREFE LL_ADC_SetCommonPathInternalCh\n + * CCR VBATE LL_ADC_SetCommonPathInternalCh + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param PathInternal This parameter can be a combination of the following values: + * @arg @ref LL_ADC_PATH_INTERNAL_NONE + * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT + * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR + * @arg @ref LL_ADC_PATH_INTERNAL_VBAT + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t PathInternal) +{ + MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE, PathInternal); +} + +/** + * @brief Get parameter common to several ADC: measurement path to internal + * channels (VrefInt, temperature sensor, ...). + * @note One or several values can be selected. + * Example: (LL_ADC_PATH_INTERNAL_VREFINT | + * LL_ADC_PATH_INTERNAL_TEMPSENSOR) + * @rmtoll CCR TSVREFE LL_ADC_GetCommonPathInternalCh\n + * CCR VBATE LL_ADC_GetCommonPathInternalCh + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Returned value can be a combination of the following values: + * @arg @ref LL_ADC_PATH_INTERNAL_NONE + * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT + * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR + * @arg @ref LL_ADC_PATH_INTERNAL_VBAT + */ +__STATIC_INLINE uint32_t LL_ADC_GetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE)); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_Instance Configuration of ADC hierarchical scope: ADC instance + * @{ + */ + +/** + * @brief Set ADC resolution. + * Refer to reference manual for alignments formats + * dependencies to ADC resolutions. + * @rmtoll CR1 RES LL_ADC_SetResolution + * @param ADCx ADC instance + * @param Resolution This parameter can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetResolution(ADC_TypeDef *ADCx, uint32_t Resolution) +{ + MODIFY_REG(ADCx->CR1, ADC_CR1_RES, Resolution); +} + +/** + * @brief Get ADC resolution. + * Refer to reference manual for alignments formats + * dependencies to ADC resolutions. + * @rmtoll CR1 RES LL_ADC_GetResolution + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_RESOLUTION_12B + * @arg @ref LL_ADC_RESOLUTION_10B + * @arg @ref LL_ADC_RESOLUTION_8B + * @arg @ref LL_ADC_RESOLUTION_6B + */ +__STATIC_INLINE uint32_t LL_ADC_GetResolution(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_RES)); +} + +/** + * @brief Set ADC conversion data alignment. + * @note Refer to reference manual for alignments formats + * dependencies to ADC resolutions. + * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment + * @param ADCx ADC instance + * @param DataAlignment This parameter can be one of the following values: + * @arg @ref LL_ADC_DATA_ALIGN_RIGHT + * @arg @ref LL_ADC_DATA_ALIGN_LEFT + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetDataAlignment(ADC_TypeDef *ADCx, uint32_t DataAlignment) +{ + MODIFY_REG(ADCx->CR2, ADC_CR2_ALIGN, DataAlignment); +} + +/** + * @brief Get ADC conversion data alignment. + * @note Refer to reference manual for alignments formats + * dependencies to ADC resolutions. + * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_DATA_ALIGN_RIGHT + * @arg @ref LL_ADC_DATA_ALIGN_LEFT + */ +__STATIC_INLINE uint32_t LL_ADC_GetDataAlignment(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_ALIGN)); +} + +/** + * @brief Set ADC sequencers scan mode, for all ADC groups + * (group regular, group injected). + * @note According to sequencers scan mode : + * - If disabled: ADC conversion is performed in unitary conversion + * mode (one channel converted, that defined in rank 1). + * Configuration of sequencers of all ADC groups + * (sequencer scan length, ...) is discarded: equivalent to + * scan length of 1 rank. + * - If enabled: ADC conversions are performed in sequence conversions + * mode, according to configuration of sequencers of + * each ADC group (sequencer scan length, ...). + * Refer to function @ref LL_ADC_REG_SetSequencerLength() + * and to function @ref LL_ADC_INJ_SetSequencerLength(). + * @rmtoll CR1 SCAN LL_ADC_SetSequencersScanMode + * @param ADCx ADC instance + * @param ScanMode This parameter can be one of the following values: + * @arg @ref LL_ADC_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_SEQ_SCAN_ENABLE + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetSequencersScanMode(ADC_TypeDef *ADCx, uint32_t ScanMode) +{ + MODIFY_REG(ADCx->CR1, ADC_CR1_SCAN, ScanMode); +} + +/** + * @brief Get ADC sequencers scan mode, for all ADC groups + * (group regular, group injected). + * @note According to sequencers scan mode : + * - If disabled: ADC conversion is performed in unitary conversion + * mode (one channel converted, that defined in rank 1). + * Configuration of sequencers of all ADC groups + * (sequencer scan length, ...) is discarded: equivalent to + * scan length of 1 rank. + * - If enabled: ADC conversions are performed in sequence conversions + * mode, according to configuration of sequencers of + * each ADC group (sequencer scan length, ...). + * Refer to function @ref LL_ADC_REG_SetSequencerLength() + * and to function @ref LL_ADC_INJ_SetSequencerLength(). + * @rmtoll CR1 SCAN LL_ADC_GetSequencersScanMode + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_SEQ_SCAN_ENABLE + */ +__STATIC_INLINE uint32_t LL_ADC_GetSequencersScanMode(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_SCAN)); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Regular Configuration of ADC hierarchical scope: group regular + * @{ + */ + +/** + * @brief Set ADC group regular conversion trigger source: + * internal (SW start) or from external IP (timer event, + * external interrupt line). + * @note On this STM32 series, setting of external trigger edge is performed + * using function @ref LL_ADC_REG_StartConversionExtTrig(). + * @note Availability of parameters of trigger sources from timer + * depends on timers availability on the selected device. + * @rmtoll CR2 EXTSEL LL_ADC_REG_SetTriggerSource\n + * CR2 EXTEN LL_ADC_REG_SetTriggerSource + * @param ADCx ADC instance + * @param TriggerSource This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_TRIG_SOFTWARE + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) +{ +/* Note: On this STM32 series, ADC group regular external trigger edge */ +/* is used to perform a ADC conversion start. */ +/* This function does not set external trigger edge. */ +/* This feature is set using function */ +/* @ref LL_ADC_REG_StartConversionExtTrig(). */ + MODIFY_REG(ADCx->CR2, ADC_CR2_EXTSEL, (TriggerSource & ADC_CR2_EXTSEL)); +} + +/** + * @brief Get ADC group regular conversion trigger source: + * internal (SW start) or from external IP (timer event, + * external interrupt line). + * @note To determine whether group regular trigger source is + * internal (SW start) or external, without detail + * of which peripheral is selected as external trigger, + * (equivalent to + * "if(LL_ADC_REG_GetTriggerSource(ADC1) == LL_ADC_REG_TRIG_SOFTWARE)") + * use function @ref LL_ADC_REG_IsTriggerSourceSWStart. + * @note Availability of parameters of trigger sources from timer + * depends on timers availability on the selected device. + * @rmtoll CR2 EXTSEL LL_ADC_REG_GetTriggerSource\n + * CR2 EXTEN LL_ADC_REG_GetTriggerSource + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_TRIG_SOFTWARE + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 + * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO + * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerSource(ADC_TypeDef *ADCx) +{ + uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_EXTSEL | ADC_CR2_EXTEN); + + /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ + /* corresponding to ADC_CR2_EXTEN {0; 1; 2; 3}. */ + uint32_t ShiftExten = ((TriggerSource & ADC_CR2_EXTEN) >> (ADC_REG_TRIG_EXTEN_BITOFFSET_POS - 2UL)); + + /* Set bitfield corresponding to ADC_CR2_EXTEN and ADC_CR2_EXTSEL */ + /* to match with triggers literals definition. */ + return ((TriggerSource + & (ADC_REG_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_EXTSEL) + | ((ADC_REG_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_EXTEN) + ); +} + +/** + * @brief Get ADC group regular conversion trigger source internal (SW start) + or external. + * @note In case of group regular trigger source set to external trigger, + * to determine which peripheral is selected as external trigger, + * use function @ref LL_ADC_REG_GetTriggerSource(). + * @rmtoll CR2 EXTEN LL_ADC_REG_IsTriggerSourceSWStart + * @param ADCx ADC instance + * @retval Value "0" if trigger source external trigger + * Value "1" if trigger source SW start. + */ +__STATIC_INLINE uint32_t LL_ADC_REG_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR2, ADC_CR2_EXTEN) == (LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN)); +} + +/** + * @brief Get ADC group regular conversion trigger polarity. + * @note Applicable only for trigger source set to external trigger. + * @note On this STM32 series, setting of external trigger edge is performed + * using function @ref LL_ADC_REG_StartConversionExtTrig(). + * @rmtoll CR2 EXTEN LL_ADC_REG_GetTriggerEdge + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_TRIG_EXT_RISING + * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING + * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerEdge(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EXTEN)); +} + + +/** + * @brief Set ADC group regular sequencer length and scan direction. + * @note Description of ADC group regular sequencer features: + * - For devices with sequencer fully configurable + * (function "LL_ADC_REG_SetSequencerRanks()" available): + * sequencer length and each rank affectation to a channel + * are configurable. + * This function performs configuration of: + * - Sequence length: Number of ranks in the scan sequence. + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from rank 1 to rank n). + * Sequencer ranks are selected using + * function "LL_ADC_REG_SetSequencerRanks()". + * - For devices with sequencer not fully configurable + * (function "LL_ADC_REG_SetSequencerChannels()" available): + * sequencer length and each rank affectation to a channel + * are defined by channel number. + * This function performs configuration of: + * - Sequence length: Number of ranks in the scan sequence is + * defined by number of channels set in the sequence, + * rank of each channel is fixed by channel HW number. + * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from lowest channel number to + * highest channel number). + * Sequencer ranks are selected using + * function "LL_ADC_REG_SetSequencerChannels()". + * @note On this STM32 series, group regular sequencer configuration + * is conditioned to ADC instance sequencer mode. + * If ADC instance sequencer mode is disabled, sequencers of + * all groups (group regular, group injected) can be configured + * but their execution is disabled (limited to rank 1). + * Refer to function @ref LL_ADC_SetSequencersScanMode(). + * @note Sequencer disabled is equivalent to sequencer of 1 rank: + * ADC conversion on only 1 channel. + * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength + * @param ADCx ADC instance + * @param SequencerNbRanks This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) +{ + MODIFY_REG(ADCx->SQR1, ADC_SQR1_L, SequencerNbRanks); +} + +/** + * @brief Get ADC group regular sequencer length and scan direction. + * @note Description of ADC group regular sequencer features: + * - For devices with sequencer fully configurable + * (function "LL_ADC_REG_SetSequencerRanks()" available): + * sequencer length and each rank affectation to a channel + * are configurable. + * This function retrieves: + * - Sequence length: Number of ranks in the scan sequence. + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from rank 1 to rank n). + * Sequencer ranks are selected using + * function "LL_ADC_REG_SetSequencerRanks()". + * - For devices with sequencer not fully configurable + * (function "LL_ADC_REG_SetSequencerChannels()" available): + * sequencer length and each rank affectation to a channel + * are defined by channel number. + * This function retrieves: + * - Sequence length: Number of ranks in the scan sequence is + * defined by number of channels set in the sequence, + * rank of each channel is fixed by channel HW number. + * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from lowest channel number to + * highest channel number). + * Sequencer ranks are selected using + * function "LL_ADC_REG_SetSequencerChannels()". + * @note On this STM32 series, group regular sequencer configuration + * is conditioned to ADC instance sequencer mode. + * If ADC instance sequencer mode is disabled, sequencers of + * all groups (group regular, group injected) can be configured + * but their execution is disabled (limited to rank 1). + * Refer to function @ref LL_ADC_SetSequencersScanMode(). + * @note Sequencer disabled is equivalent to sequencer of 1 rank: + * ADC conversion on only 1 channel. + * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS + * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerLength(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->SQR1, ADC_SQR1_L)); +} + +/** + * @brief Set ADC group regular sequencer discontinuous mode: + * sequence subdivided and scan conversions interrupted every selected + * number of ranks. + * @note It is not possible to enable both ADC group regular + * continuous mode and sequencer discontinuous mode. + * @note It is not possible to enable both ADC auto-injected mode + * and ADC group regular sequencer discontinuous mode. + * @rmtoll CR1 DISCEN LL_ADC_REG_SetSequencerDiscont\n + * CR1 DISCNUM LL_ADC_REG_SetSequencerDiscont + * @param ADCx ADC instance + * @param SeqDiscont This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE + * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK + * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) +{ + MODIFY_REG(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM, SeqDiscont); +} + +/** + * @brief Get ADC group regular sequencer discontinuous mode: + * sequence subdivided and scan conversions interrupted every selected + * number of ranks. + * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont\n + * CR1 DISCNUM LL_ADC_REG_GetSequencerDiscont + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE + * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK + * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS + * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerDiscont(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM)); +} + +/** + * @brief Set ADC group regular sequence: channel on the selected + * scan sequence rank. + * @note This function performs configuration of: + * - Channels ordering into each rank of scan sequence: + * whatever channel can be placed into whatever rank. + * @note On this STM32 series, ADC group regular sequencer is + * fully configurable: sequencer length and each rank + * affectation to a channel are configurable. + * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). + * @note Depending on devices and packages, some channels may not be available. + * Refer to device datasheet for channels availability. + * @note On this STM32 series, to measure internal channels (VrefInt, + * TempSensor, ...), measurement paths to internal channels must be + * enabled separately. + * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). + * @rmtoll SQR3 SQ1 LL_ADC_REG_SetSequencerRanks\n + * SQR3 SQ2 LL_ADC_REG_SetSequencerRanks\n + * SQR3 SQ3 LL_ADC_REG_SetSequencerRanks\n + * SQR3 SQ4 LL_ADC_REG_SetSequencerRanks\n + * SQR3 SQ5 LL_ADC_REG_SetSequencerRanks\n + * SQR3 SQ6 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ7 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ8 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ9 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ10 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ11 LL_ADC_REG_SetSequencerRanks\n + * SQR2 SQ12 LL_ADC_REG_SetSequencerRanks\n + * SQR1 SQ13 LL_ADC_REG_SetSequencerRanks\n + * SQR1 SQ14 LL_ADC_REG_SetSequencerRanks\n + * SQR1 SQ15 LL_ADC_REG_SetSequencerRanks\n + * SQR1 SQ16 LL_ADC_REG_SetSequencerRanks + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_RANK_1 + * @arg @ref LL_ADC_REG_RANK_2 + * @arg @ref LL_ADC_REG_RANK_3 + * @arg @ref LL_ADC_REG_RANK_4 + * @arg @ref LL_ADC_REG_RANK_5 + * @arg @ref LL_ADC_REG_RANK_6 + * @arg @ref LL_ADC_REG_RANK_7 + * @arg @ref LL_ADC_REG_RANK_8 + * @arg @ref LL_ADC_REG_RANK_9 + * @arg @ref LL_ADC_REG_RANK_10 + * @arg @ref LL_ADC_REG_RANK_11 + * @arg @ref LL_ADC_REG_RANK_12 + * @arg @ref LL_ADC_REG_RANK_13 + * @arg @ref LL_ADC_REG_RANK_14 + * @arg @ref LL_ADC_REG_RANK_15 + * @arg @ref LL_ADC_REG_RANK_16 + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) +{ + /* Set bits with content of parameter "Channel" with bits position */ + /* in register and register position depending on parameter "Rank". */ + /* Parameters "Rank" and "Channel" are used with masks because containing */ + /* other bits reserved for other purpose. */ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); + + MODIFY_REG(*preg, + ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK), + (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (Rank & ADC_REG_RANK_ID_SQRX_MASK)); +} + +/** + * @brief Get ADC group regular sequence: channel on the selected + * scan sequence rank. + * @note On this STM32 series, ADC group regular sequencer is + * fully configurable: sequencer length and each rank + * affectation to a channel are configurable. + * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). + * @note Depending on devices and packages, some channels may not be available. + * Refer to device datasheet for channels availability. + * @note Usage of the returned channel number: + * - To reinject this channel into another function LL_ADC_xxx: + * the returned channel number is only partly formatted on definition + * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared + * with parts of literals LL_ADC_CHANNEL_x or using + * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * Then the selected literal LL_ADC_CHANNEL_x can be used + * as parameter for another function. + * - To get the channel number in decimal format: + * process the returned value with the helper macro + * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * @rmtoll SQR3 SQ1 LL_ADC_REG_GetSequencerRanks\n + * SQR3 SQ2 LL_ADC_REG_GetSequencerRanks\n + * SQR3 SQ3 LL_ADC_REG_GetSequencerRanks\n + * SQR3 SQ4 LL_ADC_REG_GetSequencerRanks\n + * SQR3 SQ5 LL_ADC_REG_GetSequencerRanks\n + * SQR3 SQ6 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ7 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ8 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ9 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ10 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ11 LL_ADC_REG_GetSequencerRanks\n + * SQR2 SQ12 LL_ADC_REG_GetSequencerRanks\n + * SQR1 SQ13 LL_ADC_REG_GetSequencerRanks\n + * SQR1 SQ14 LL_ADC_REG_GetSequencerRanks\n + * SQR1 SQ15 LL_ADC_REG_GetSequencerRanks\n + * SQR1 SQ16 LL_ADC_REG_GetSequencerRanks + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_RANK_1 + * @arg @ref LL_ADC_REG_RANK_2 + * @arg @ref LL_ADC_REG_RANK_3 + * @arg @ref LL_ADC_REG_RANK_4 + * @arg @ref LL_ADC_REG_RANK_5 + * @arg @ref LL_ADC_REG_RANK_6 + * @arg @ref LL_ADC_REG_RANK_7 + * @arg @ref LL_ADC_REG_RANK_8 + * @arg @ref LL_ADC_REG_RANK_9 + * @arg @ref LL_ADC_REG_RANK_10 + * @arg @ref LL_ADC_REG_RANK_11 + * @arg @ref LL_ADC_REG_RANK_12 + * @arg @ref LL_ADC_REG_RANK_13 + * @arg @ref LL_ADC_REG_RANK_14 + * @arg @ref LL_ADC_REG_RANK_15 + * @arg @ref LL_ADC_REG_RANK_16 + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n + * (1) For ADC channel read back from ADC register, + * comparison with internal channel parameter to be done + * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); + + return (uint32_t) (READ_BIT(*preg, + ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK)) + >> (Rank & ADC_REG_RANK_ID_SQRX_MASK) + ); +} + +/** + * @brief Set ADC continuous conversion mode on ADC group regular. + * @note Description of ADC continuous conversion mode: + * - single mode: one conversion per trigger + * - continuous mode: after the first trigger, following + * conversions launched successively automatically. + * @note It is not possible to enable both ADC group regular + * continuous mode and sequencer discontinuous mode. + * @rmtoll CR2 CONT LL_ADC_REG_SetContinuousMode + * @param ADCx ADC instance + * @param Continuous This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_CONV_SINGLE + * @arg @ref LL_ADC_REG_CONV_CONTINUOUS + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetContinuousMode(ADC_TypeDef *ADCx, uint32_t Continuous) +{ + MODIFY_REG(ADCx->CR2, ADC_CR2_CONT, Continuous); +} + +/** + * @brief Get ADC continuous conversion mode on ADC group regular. + * @note Description of ADC continuous conversion mode: + * - single mode: one conversion per trigger + * - continuous mode: after the first trigger, following + * conversions launched successively automatically. + * @rmtoll CR2 CONT LL_ADC_REG_GetContinuousMode + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_CONV_SINGLE + * @arg @ref LL_ADC_REG_CONV_CONTINUOUS + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetContinuousMode(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_CONT)); +} + +/** + * @brief Set ADC group regular conversion data transfer: no transfer or + * transfer by DMA, and DMA requests mode. + * @note If transfer by DMA selected, specifies the DMA requests + * mode: + * - Limited mode (One shot mode): DMA transfer requests are stopped + * when number of DMA data transfers (number of + * ADC conversions) is reached. + * This ADC mode is intended to be used with DMA mode non-circular. + * - Unlimited mode: DMA transfer requests are unlimited, + * whatever number of DMA data transfers (number of + * ADC conversions). + * This ADC mode is intended to be used with DMA mode circular. + * @note If ADC DMA requests mode is set to unlimited and DMA is set to + * mode non-circular: + * when DMA transfers size will be reached, DMA will stop transfers of + * ADC conversions data ADC will raise an overrun error + * (overrun flag and interruption if enabled). + * @note For devices with several ADC instances: ADC multimode DMA + * settings are available using function @ref LL_ADC_SetMultiDMATransfer(). + * @note To configure DMA source address (peripheral address), + * use function @ref LL_ADC_DMA_GetRegAddr(). + * @rmtoll CR2 DMA LL_ADC_REG_SetDMATransfer\n + * CR2 DDS LL_ADC_REG_SetDMATransfer + * @param ADCx ADC instance + * @param DMATransfer This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE + * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED + * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetDMATransfer(ADC_TypeDef *ADCx, uint32_t DMATransfer) +{ + MODIFY_REG(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS, DMATransfer); +} + +/** + * @brief Get ADC group regular conversion data transfer: no transfer or + * transfer by DMA, and DMA requests mode. + * @note If transfer by DMA selected, specifies the DMA requests + * mode: + * - Limited mode (One shot mode): DMA transfer requests are stopped + * when number of DMA data transfers (number of + * ADC conversions) is reached. + * This ADC mode is intended to be used with DMA mode non-circular. + * - Unlimited mode: DMA transfer requests are unlimited, + * whatever number of DMA data transfers (number of + * ADC conversions). + * This ADC mode is intended to be used with DMA mode circular. + * @note If ADC DMA requests mode is set to unlimited and DMA is set to + * mode non-circular: + * when DMA transfers size will be reached, DMA will stop transfers of + * ADC conversions data ADC will raise an overrun error + * (overrun flag and interruption if enabled). + * @note For devices with several ADC instances: ADC multimode DMA + * settings are available using function @ref LL_ADC_GetMultiDMATransfer(). + * @note To configure DMA source address (peripheral address), + * use function @ref LL_ADC_DMA_GetRegAddr(). + * @rmtoll CR2 DMA LL_ADC_REG_GetDMATransfer\n + * CR2 DDS LL_ADC_REG_GetDMATransfer + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE + * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED + * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetDMATransfer(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS)); +} + +/** + * @brief Specify which ADC flag between EOC (end of unitary conversion) + * or EOS (end of sequence conversions) is used to indicate + * the end of conversion. + * @note This feature is aimed to be set when using ADC with + * programming model by polling or interruption + * (programming model by DMA usually uses DMA interruptions + * to indicate end of conversion and data transfer). + * @note For ADC group injected, end of conversion (flag&IT) is raised + * only at the end of the sequence. + * @rmtoll CR2 EOCS LL_ADC_REG_SetFlagEndOfConversion + * @param ADCx ADC instance + * @param EocSelection This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV + * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_SetFlagEndOfConversion(ADC_TypeDef *ADCx, uint32_t EocSelection) +{ + MODIFY_REG(ADCx->CR2, ADC_CR2_EOCS, EocSelection); +} + +/** + * @brief Get which ADC flag between EOC (end of unitary conversion) + * or EOS (end of sequence conversions) is used to indicate + * the end of conversion. + * @rmtoll CR2 EOCS LL_ADC_REG_GetFlagEndOfConversion + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV + * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV + */ +__STATIC_INLINE uint32_t LL_ADC_REG_GetFlagEndOfConversion(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EOCS)); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Injected Configuration of ADC hierarchical scope: group injected + * @{ + */ + +/** + * @brief Set ADC group injected conversion trigger source: + * internal (SW start) or from external IP (timer event, + * external interrupt line). + * @note On this STM32 series, setting of external trigger edge is performed + * using function @ref LL_ADC_INJ_StartConversionExtTrig(). + * @note Availability of parameters of trigger sources from timer + * depends on timers availability on the selected device. + * @rmtoll CR2 JEXTSEL LL_ADC_INJ_SetTriggerSource\n + * CR2 JEXTEN LL_ADC_INJ_SetTriggerSource + * @param ADCx ADC instance + * @param TriggerSource This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) +{ +/* Note: On this STM32 series, ADC group injected external trigger edge */ +/* is used to perform a ADC conversion start. */ +/* This function does not set external trigger edge. */ +/* This feature is set using function */ +/* @ref LL_ADC_INJ_StartConversionExtTrig(). */ + MODIFY_REG(ADCx->CR2, ADC_CR2_JEXTSEL, (TriggerSource & ADC_CR2_JEXTSEL)); +} + +/** + * @brief Get ADC group injected conversion trigger source: + * internal (SW start) or from external IP (timer event, + * external interrupt line). + * @note To determine whether group injected trigger source is + * internal (SW start) or external, without detail + * of which peripheral is selected as external trigger, + * (equivalent to + * "if(LL_ADC_INJ_GetTriggerSource(ADC1) == LL_ADC_INJ_TRIG_SOFTWARE)") + * use function @ref LL_ADC_INJ_IsTriggerSourceSWStart. + * @note Availability of parameters of trigger sources from timer + * depends on timers availability on the selected device. + * @rmtoll CR2 JEXTSEL LL_ADC_INJ_GetTriggerSource\n + * CR2 JEXTEN LL_ADC_INJ_GetTriggerSource + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 + * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 + * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerSource(ADC_TypeDef *ADCx) +{ + uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_JEXTSEL | ADC_CR2_JEXTEN); + + /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ + /* corresponding to ADC_CR2_JEXTEN {0; 1; 2; 3}. */ + uint32_t ShiftExten = ((TriggerSource & ADC_CR2_JEXTEN) >> (ADC_INJ_TRIG_EXTEN_BITOFFSET_POS - 2UL)); + + /* Set bitfield corresponding to ADC_CR2_JEXTEN and ADC_CR2_JEXTSEL */ + /* to match with triggers literals definition. */ + return ((TriggerSource + & (ADC_INJ_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_JEXTSEL) + | ((ADC_INJ_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_JEXTEN) + ); +} + +/** + * @brief Get ADC group injected conversion trigger source internal (SW start) + or external + * @note In case of group injected trigger source set to external trigger, + * to determine which peripheral is selected as external trigger, + * use function @ref LL_ADC_INJ_GetTriggerSource. + * @rmtoll CR2 JEXTEN LL_ADC_INJ_IsTriggerSourceSWStart + * @param ADCx ADC instance + * @retval Value "0" if trigger source external trigger + * Value "1" if trigger source SW start. + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN) == (LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN)); +} + +/** + * @brief Get ADC group injected conversion trigger polarity. + * Applicable only for trigger source set to external trigger. + * @rmtoll CR2 JEXTEN LL_ADC_INJ_GetTriggerEdge + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING + * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING + * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerEdge(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN)); +} + +/** + * @brief Set ADC group injected sequencer length and scan direction. + * @note This function performs configuration of: + * - Sequence length: Number of ranks in the scan sequence. + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from rank 1 to rank n). + * @note On this STM32 series, group injected sequencer configuration + * is conditioned to ADC instance sequencer mode. + * If ADC instance sequencer mode is disabled, sequencers of + * all groups (group regular, group injected) can be configured + * but their execution is disabled (limited to rank 1). + * Refer to function @ref LL_ADC_SetSequencersScanMode(). + * @note Sequencer disabled is equivalent to sequencer of 1 rank: + * ADC conversion on only 1 channel. + * @rmtoll JSQR JL LL_ADC_INJ_SetSequencerLength + * @param ADCx ADC instance + * @param SequencerNbRanks This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) +{ + MODIFY_REG(ADCx->JSQR, ADC_JSQR_JL, SequencerNbRanks); +} + +/** + * @brief Get ADC group injected sequencer length and scan direction. + * @note This function retrieves: + * - Sequence length: Number of ranks in the scan sequence. + * - Sequence direction: Unless specified in parameters, sequencer + * scan direction is forward (from rank 1 to rank n). + * @note On this STM32 series, group injected sequencer configuration + * is conditioned to ADC instance sequencer mode. + * If ADC instance sequencer mode is disabled, sequencers of + * all groups (group regular, group injected) can be configured + * but their execution is disabled (limited to rank 1). + * Refer to function @ref LL_ADC_SetSequencersScanMode(). + * @note Sequencer disabled is equivalent to sequencer of 1 rank: + * ADC conversion on only 1 channel. + * @rmtoll JSQR JL LL_ADC_INJ_GetSequencerLength + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS + * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerLength(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->JSQR, ADC_JSQR_JL)); +} + +/** + * @brief Set ADC group injected sequencer discontinuous mode: + * sequence subdivided and scan conversions interrupted every selected + * number of ranks. + * @note It is not possible to enable both ADC group injected + * auto-injected mode and sequencer discontinuous mode. + * @rmtoll CR1 DISCEN LL_ADC_INJ_SetSequencerDiscont + * @param ADCx ADC instance + * @param SeqDiscont This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE + * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) +{ + MODIFY_REG(ADCx->CR1, ADC_CR1_JDISCEN, SeqDiscont); +} + +/** + * @brief Get ADC group injected sequencer discontinuous mode: + * sequence subdivided and scan conversions interrupted every selected + * number of ranks. + * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE + * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerDiscont(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JDISCEN)); +} + +/** + * @brief Set ADC group injected sequence: channel on the selected + * sequence rank. + * @note Depending on devices and packages, some channels may not be available. + * Refer to device datasheet for channels availability. + * @note On this STM32 series, to measure internal channels (VrefInt, + * TempSensor, ...), measurement paths to internal channels must be + * enabled separately. + * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). + * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) +{ + /* Set bits with content of parameter "Channel" with bits position */ + /* in register depending on parameter "Rank". */ + /* Parameters "Rank" and "Channel" are used with masks because containing */ + /* other bits reserved for other purpose. */ + uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; + + MODIFY_REG(ADCx->JSQR, + ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))), + (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))); +} + +/** + * @brief Get ADC group injected sequence: channel on the selected + * sequence rank. + * @note Depending on devices and packages, some channels may not be available. + * Refer to device datasheet for channels availability. + * @note Usage of the returned channel number: + * - To reinject this channel into another function LL_ADC_xxx: + * the returned channel number is only partly formatted on definition + * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared + * with parts of literals LL_ADC_CHANNEL_x or using + * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * Then the selected literal LL_ADC_CHANNEL_x can be used + * as parameter for another function. + * - To get the channel number in decimal format: + * process the returned value with the helper macro + * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n + * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n + * (1) For ADC channel read back from ADC register, + * comparison with internal channel parameter to be done + * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) +{ + uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; + + return (uint32_t)(READ_BIT(ADCx->JSQR, + ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))) + >> (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))) + ); +} + +/** + * @brief Set ADC group injected conversion trigger: + * independent or from ADC group regular. + * @note This mode can be used to extend number of data registers + * updated after one ADC conversion trigger and with data + * permanently kept (not erased by successive conversions of scan of + * ADC sequencer ranks), up to 5 data registers: + * 1 data register on ADC group regular, 4 data registers + * on ADC group injected. + * @note If ADC group injected injected trigger source is set to an + * external trigger, this feature must be must be set to + * independent trigger. + * ADC group injected automatic trigger is compliant only with + * group injected trigger source set to SW start, without any + * further action on ADC group injected conversion start or stop: + * in this case, ADC group injected is controlled only + * from ADC group regular. + * @note It is not possible to enable both ADC group injected + * auto-injected mode and sequencer discontinuous mode. + * @rmtoll CR1 JAUTO LL_ADC_INJ_SetTrigAuto + * @param ADCx ADC instance + * @param TrigAuto This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT + * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetTrigAuto(ADC_TypeDef *ADCx, uint32_t TrigAuto) +{ + MODIFY_REG(ADCx->CR1, ADC_CR1_JAUTO, TrigAuto); +} + +/** + * @brief Get ADC group injected conversion trigger: + * independent or from ADC group regular. + * @rmtoll CR1 JAUTO LL_ADC_INJ_GetTrigAuto + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT + * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetTrigAuto(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JAUTO)); +} + +/** + * @brief Set ADC group injected offset. + * @note It sets: + * - ADC group injected rank to which the offset programmed + * will be applied + * - Offset level (offset to be subtracted from the raw + * converted data). + * Caution: Offset format is dependent to ADC resolution: + * offset has to be left-aligned on bit 11, the LSB (right bits) + * are set to 0. + * @note Offset cannot be enabled or disabled. + * To emulate offset disabled, set an offset value equal to 0. + * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_SetOffset\n + * JOFR2 JOFFSET2 LL_ADC_INJ_SetOffset\n + * JOFR3 JOFFSET3 LL_ADC_INJ_SetOffset\n + * JOFR4 JOFFSET4 LL_ADC_INJ_SetOffset + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @param OffsetLevel Value between Min_Data=0x000 and Max_Data=0xFFF + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_SetOffset(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t OffsetLevel) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); + + MODIFY_REG(*preg, + ADC_JOFR1_JOFFSET1, + OffsetLevel); +} + +/** + * @brief Get ADC group injected offset. + * @note It gives offset level (offset to be subtracted from the raw converted data). + * Caution: Offset format is dependent to ADC resolution: + * offset has to be left-aligned on bit 11, the LSB (right bits) + * are set to 0. + * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_GetOffset\n + * JOFR2 JOFFSET2 LL_ADC_INJ_GetOffset\n + * JOFR3 JOFFSET3 LL_ADC_INJ_GetOffset\n + * JOFR4 JOFFSET4 LL_ADC_INJ_GetOffset + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_GetOffset(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); + + return (uint32_t)(READ_BIT(*preg, + ADC_JOFR1_JOFFSET1) + ); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_Channels Configuration of ADC hierarchical scope: channels + * @{ + */ + +/** + * @brief Set sampling time of the selected ADC channel + * Unit: ADC clock cycles. + * @note On this device, sampling time is on channel scope: independently + * of channel mapped on ADC group regular or injected. + * @note In case of internal channel (VrefInt, TempSensor, ...) to be + * converted: + * sampling time constraints must be respected (sampling time can be + * adjusted in function of ADC clock frequency and sampling time + * setting). + * Refer to device datasheet for timings values (parameters TS_vrefint, + * TS_temp, ...). + * @note Conversion time is the addition of sampling time and processing time. + * Refer to reference manual for ADC processing time of + * this STM32 series. + * @note In case of ADC conversion of internal channel (VrefInt, + * temperature sensor, ...), a sampling time minimum value + * is required. + * Refer to device datasheet. + * @rmtoll SMPR1 SMP18 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP17 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP16 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP15 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP14 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP13 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP12 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP11 LL_ADC_SetChannelSamplingTime\n + * SMPR1 SMP10 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP9 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP8 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP7 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP6 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP5 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP4 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP3 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP2 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP1 LL_ADC_SetChannelSamplingTime\n + * SMPR2 SMP0 LL_ADC_SetChannelSamplingTime + * @param ADCx ADC instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @param SamplingTime This parameter can be one of the following values: + * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel, uint32_t SamplingTime) +{ + /* Set bits with content of parameter "SamplingTime" with bits position */ + /* in register and register position depending on parameter "Channel". */ + /* Parameter "Channel" is used with masks because containing */ + /* other bits reserved for other purpose. */ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); + + MODIFY_REG(*preg, + ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK), + SamplingTime << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)); +} + +/** + * @brief Get sampling time of the selected ADC channel + * Unit: ADC clock cycles. + * @note On this device, sampling time is on channel scope: independently + * of channel mapped on ADC group regular or injected. + * @note Conversion time is the addition of sampling time and processing time. + * Refer to reference manual for ADC processing time of + * this STM32 series. + * @rmtoll SMPR1 SMP18 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP17 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP16 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP15 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP14 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP13 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP12 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP11 LL_ADC_GetChannelSamplingTime\n + * SMPR1 SMP10 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP9 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP8 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP7 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP6 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP5 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP4 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP3 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP2 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP1 LL_ADC_GetChannelSamplingTime\n + * SMPR2 SMP0 LL_ADC_GetChannelSamplingTime + * @param ADCx ADC instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_ADC_CHANNEL_0 + * @arg @ref LL_ADC_CHANNEL_1 + * @arg @ref LL_ADC_CHANNEL_2 + * @arg @ref LL_ADC_CHANNEL_3 + * @arg @ref LL_ADC_CHANNEL_4 + * @arg @ref LL_ADC_CHANNEL_5 + * @arg @ref LL_ADC_CHANNEL_6 + * @arg @ref LL_ADC_CHANNEL_7 + * @arg @ref LL_ADC_CHANNEL_8 + * @arg @ref LL_ADC_CHANNEL_9 + * @arg @ref LL_ADC_CHANNEL_10 + * @arg @ref LL_ADC_CHANNEL_11 + * @arg @ref LL_ADC_CHANNEL_12 + * @arg @ref LL_ADC_CHANNEL_13 + * @arg @ref LL_ADC_CHANNEL_14 + * @arg @ref LL_ADC_CHANNEL_15 + * @arg @ref LL_ADC_CHANNEL_16 + * @arg @ref LL_ADC_CHANNEL_17 + * @arg @ref LL_ADC_CHANNEL_18 + * @arg @ref LL_ADC_CHANNEL_VREFINT (1) + * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) + * @arg @ref LL_ADC_CHANNEL_VBAT (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES + * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES + */ +__STATIC_INLINE uint32_t LL_ADC_GetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); + + return (uint32_t)(READ_BIT(*preg, + ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)) + >> __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK) + ); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_AnalogWatchdog Configuration of ADC transversal scope: analog watchdog + * @{ + */ + +/** + * @brief Set ADC analog watchdog monitored channels: + * a single channel or all channels, + * on ADC groups regular and-or injected. + * @note Once monitored channels are selected, analog watchdog + * is enabled. + * @note In case of need to define a single channel to monitor + * with analog watchdog from sequencer channel definition, + * use helper macro @ref __LL_ADC_ANALOGWD_CHANNEL_GROUP(). + * @note On this STM32 series, there is only 1 kind of analog watchdog + * instance: + * - AWD standard (instance AWD1): + * - channels monitored: can monitor 1 channel or all channels. + * - groups monitored: ADC groups regular and-or injected. + * - resolution: resolution is not limited (corresponds to + * ADC resolution configured). + * @rmtoll CR1 AWD1CH LL_ADC_SetAnalogWDMonitChannels\n + * CR1 AWD1SGL LL_ADC_SetAnalogWDMonitChannels\n + * CR1 AWD1EN LL_ADC_SetAnalogWDMonitChannels + * @param ADCx ADC instance + * @param AWDChannelGroup This parameter can be one of the following values: + * @arg @ref LL_ADC_AWD_DISABLE + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG + * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG + * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG + * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG + * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG + * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG + * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG + * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG + * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG + * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG + * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG + * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG + * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG + * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG + * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG + * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG + * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG + * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG + * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG + * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ + * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) + * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) + * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) + * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) + * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) + * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) + * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) + * + * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n + * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetAnalogWDMonitChannels(ADC_TypeDef *ADCx, uint32_t AWDChannelGroup) +{ + MODIFY_REG(ADCx->CR1, + (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH), + AWDChannelGroup); +} + +/** + * @brief Get ADC analog watchdog monitored channel. + * @note Usage of the returned channel number: + * - To reinject this channel into another function LL_ADC_xxx: + * the returned channel number is only partly formatted on definition + * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared + * with parts of literals LL_ADC_CHANNEL_x or using + * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * Then the selected literal LL_ADC_CHANNEL_x can be used + * as parameter for another function. + * - To get the channel number in decimal format: + * process the returned value with the helper macro + * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). + * Applicable only when the analog watchdog is set to monitor + * one channel. + * @note On this STM32 series, there is only 1 kind of analog watchdog + * instance: + * - AWD standard (instance AWD1): + * - channels monitored: can monitor 1 channel or all channels. + * - groups monitored: ADC groups regular and-or injected. + * - resolution: resolution is not limited (corresponds to + * ADC resolution configured). + * @rmtoll CR1 AWD1CH LL_ADC_GetAnalogWDMonitChannels\n + * CR1 AWD1SGL LL_ADC_GetAnalogWDMonitChannels\n + * CR1 AWD1EN LL_ADC_GetAnalogWDMonitChannels + * @param ADCx ADC instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_AWD_DISABLE + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ + * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG + * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG + * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG + * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG + * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG + * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG + * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG + * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG + * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG + * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG + * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG + * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG + * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG + * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG + * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG + * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG + * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG + * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG + * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG + * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ + * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ + */ +__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDMonitChannels(ADC_TypeDef *ADCx) +{ + return (uint32_t)(READ_BIT(ADCx->CR1, (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH))); +} + +/** + * @brief Set ADC analog watchdog threshold value of threshold + * high or low. + * @note In case of ADC resolution different of 12 bits, + * analog watchdog thresholds data require a specific shift. + * Use helper macro @ref __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(). + * @note On this STM32 series, there is only 1 kind of analog watchdog + * instance: + * - AWD standard (instance AWD1): + * - channels monitored: can monitor 1 channel or all channels. + * - groups monitored: ADC groups regular and-or injected. + * - resolution: resolution is not limited (corresponds to + * ADC resolution configured). + * @rmtoll HTR HT LL_ADC_SetAnalogWDThresholds\n + * LTR LT LL_ADC_SetAnalogWDThresholds + * @param ADCx ADC instance + * @param AWDThresholdsHighLow This parameter can be one of the following values: + * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH + * @arg @ref LL_ADC_AWD_THRESHOLD_LOW + * @param AWDThresholdValue Value between Min_Data=0x000 and Max_Data=0xFFF + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow, uint32_t AWDThresholdValue) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); + + MODIFY_REG(*preg, + ADC_HTR_HT, + AWDThresholdValue); +} + +/** + * @brief Get ADC analog watchdog threshold value of threshold high or + * threshold low. + * @note In case of ADC resolution different of 12 bits, + * analog watchdog thresholds data require a specific shift. + * Use helper macro @ref __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(). + * @rmtoll HTR HT LL_ADC_GetAnalogWDThresholds\n + * LTR LT LL_ADC_GetAnalogWDThresholds + * @param ADCx ADC instance + * @param AWDThresholdsHighLow This parameter can be one of the following values: + * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH + * @arg @ref LL_ADC_AWD_THRESHOLD_LOW + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF +*/ +__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); + + return (uint32_t)(READ_BIT(*preg, ADC_HTR_HT)); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Configuration_ADC_Multimode Configuration of ADC hierarchical scope: multimode + * @{ + */ + +#if defined(ADC_MULTIMODE_SUPPORT) +/** + * @brief Set ADC multimode configuration to operate in independent mode + * or multimode (for devices with several ADC instances). + * @note If multimode configuration: the selected ADC instance is + * either master or slave depending on hardware. + * Refer to reference manual. + * @rmtoll CCR MULTI LL_ADC_SetMultimode + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param Multimode This parameter can be one of the following values: + * @arg @ref LL_ADC_MULTI_INDEPENDENT + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT + * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL + * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT + * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT + * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT + * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL + * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetMultimode(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t Multimode) +{ + MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_MULTI, Multimode); +} + +/** + * @brief Get ADC multimode configuration to operate in independent mode + * or multimode (for devices with several ADC instances). + * @note If multimode configuration: the selected ADC instance is + * either master or slave depending on hardware. + * Refer to reference manual. + * @rmtoll CCR MULTI LL_ADC_GetMultimode + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_MULTI_INDEPENDENT + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT + * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL + * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT + * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM + * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT + * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT + * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT + * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL + * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN + */ +__STATIC_INLINE uint32_t LL_ADC_GetMultimode(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_MULTI)); +} + +/** + * @brief Set ADC multimode conversion data transfer: no transfer + * or transfer by DMA. + * @note If ADC multimode transfer by DMA is not selected: + * each ADC uses its own DMA channel, with its individual + * DMA transfer settings. + * If ADC multimode transfer by DMA is selected: + * One DMA channel is used for both ADC (DMA of ADC master) + * Specifies the DMA requests mode: + * - Limited mode (One shot mode): DMA transfer requests are stopped + * when number of DMA data transfers (number of + * ADC conversions) is reached. + * This ADC mode is intended to be used with DMA mode non-circular. + * - Unlimited mode: DMA transfer requests are unlimited, + * whatever number of DMA data transfers (number of + * ADC conversions). + * This ADC mode is intended to be used with DMA mode circular. + * @note If ADC DMA requests mode is set to unlimited and DMA is set to + * mode non-circular: + * when DMA transfers size will be reached, DMA will stop transfers of + * ADC conversions data ADC will raise an overrun error + * (overrun flag and interruption if enabled). + * @note How to retrieve multimode conversion data: + * Whatever multimode transfer by DMA setting: using function + * @ref LL_ADC_REG_ReadMultiConversionData32(). + * If ADC multimode transfer by DMA is selected: conversion data + * is a raw data with ADC master and slave concatenated. + * A macro is available to get the conversion data of + * ADC master or ADC slave: see helper macro + * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). + * @rmtoll CCR MDMA LL_ADC_SetMultiDMATransfer\n + * CCR DDS LL_ADC_SetMultiDMATransfer + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param MultiDMATransfer This parameter can be one of the following values: + * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiDMATransfer) +{ + MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS, MultiDMATransfer); +} + +/** + * @brief Get ADC multimode conversion data transfer: no transfer + * or transfer by DMA. + * @note If ADC multimode transfer by DMA is not selected: + * each ADC uses its own DMA channel, with its individual + * DMA transfer settings. + * If ADC multimode transfer by DMA is selected: + * One DMA channel is used for both ADC (DMA of ADC master) + * Specifies the DMA requests mode: + * - Limited mode (One shot mode): DMA transfer requests are stopped + * when number of DMA data transfers (number of + * ADC conversions) is reached. + * This ADC mode is intended to be used with DMA mode non-circular. + * - Unlimited mode: DMA transfer requests are unlimited, + * whatever number of DMA data transfers (number of + * ADC conversions). + * This ADC mode is intended to be used with DMA mode circular. + * @note If ADC DMA requests mode is set to unlimited and DMA is set to + * mode non-circular: + * when DMA transfers size will be reached, DMA will stop transfers of + * ADC conversions data ADC will raise an overrun error + * (overrun flag and interruption if enabled). + * @note How to retrieve multimode conversion data: + * Whatever multimode transfer by DMA setting: using function + * @ref LL_ADC_REG_ReadMultiConversionData32(). + * If ADC multimode transfer by DMA is selected: conversion data + * is a raw data with ADC master and slave concatenated. + * A macro is available to get the conversion data of + * ADC master or ADC slave: see helper macro + * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). + * @rmtoll CCR MDMA LL_ADC_GetMultiDMATransfer\n + * CCR DDS LL_ADC_GetMultiDMATransfer + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 + * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 + * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 + */ +__STATIC_INLINE uint32_t LL_ADC_GetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS)); +} + +/** + * @brief Set ADC multimode delay between 2 sampling phases. + * @note The sampling delay range depends on ADC resolution: + * - ADC resolution 12 bits can have maximum delay of 12 cycles. + * - ADC resolution 10 bits can have maximum delay of 10 cycles. + * - ADC resolution 8 bits can have maximum delay of 8 cycles. + * - ADC resolution 6 bits can have maximum delay of 6 cycles. + * @rmtoll CCR DELAY LL_ADC_SetMultiTwoSamplingDelay + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param MultiTwoSamplingDelay This parameter can be one of the following values: + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES + * @retval None + */ +__STATIC_INLINE void LL_ADC_SetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiTwoSamplingDelay) +{ + MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DELAY, MultiTwoSamplingDelay); +} + +/** + * @brief Get ADC multimode delay between 2 sampling phases. + * @rmtoll CCR DELAY LL_ADC_GetMultiTwoSamplingDelay + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval Returned value can be one of the following values: + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES + * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES + */ +__STATIC_INLINE uint32_t LL_ADC_GetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DELAY)); +} +#endif /* ADC_MULTIMODE_SUPPORT */ + +/** + * @} + */ +/** @defgroup ADC_LL_EF_Operation_ADC_Instance Operation on ADC hierarchical scope: ADC instance + * @{ + */ + +/** + * @brief Enable the selected ADC instance. + * @note On this STM32 series, after ADC enable, a delay for + * ADC internal analog stabilization is required before performing a + * ADC conversion start. + * Refer to device datasheet, parameter tSTAB. + * @rmtoll CR2 ADON LL_ADC_Enable + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_Enable(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR2, ADC_CR2_ADON); +} + +/** + * @brief Disable the selected ADC instance. + * @rmtoll CR2 ADON LL_ADC_Disable + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_Disable(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR2, ADC_CR2_ADON); +} + +/** + * @brief Get the selected ADC instance enable state. + * @rmtoll CR2 ADON LL_ADC_IsEnabled + * @param ADCx ADC instance + * @retval 0: ADC is disabled, 1: ADC is enabled. + */ +__STATIC_INLINE uint32_t LL_ADC_IsEnabled(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR2, ADC_CR2_ADON) == (ADC_CR2_ADON)); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Operation_ADC_Group_Regular Operation on ADC hierarchical scope: group regular + * @{ + */ + +/** + * @brief Start ADC group regular conversion. + * @note On this STM32 series, this function is relevant only for + * internal trigger (SW start), not for external trigger: + * - If ADC trigger has been set to software start, ADC conversion + * starts immediately. + * - If ADC trigger has been set to external trigger, ADC conversion + * start must be performed using function + * @ref LL_ADC_REG_StartConversionExtTrig(). + * (if external trigger edge would have been set during ADC other + * settings, ADC conversion would start at trigger event + * as soon as ADC is enabled). + * @rmtoll CR2 SWSTART LL_ADC_REG_StartConversionSWStart + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_StartConversionSWStart(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR2, ADC_CR2_SWSTART); +} + +/** + * @brief Start ADC group regular conversion from external trigger. + * @note ADC conversion will start at next trigger event (on the selected + * trigger edge) following the ADC start conversion command. + * @note On this STM32 series, this function is relevant for + * ADC conversion start from external trigger. + * If internal trigger (SW start) is needed, perform ADC conversion + * start using function @ref LL_ADC_REG_StartConversionSWStart(). + * @rmtoll CR2 EXTEN LL_ADC_REG_StartConversionExtTrig + * @param ExternalTriggerEdge This parameter can be one of the following values: + * @arg @ref LL_ADC_REG_TRIG_EXT_RISING + * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING + * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) +{ + SET_BIT(ADCx->CR2, ExternalTriggerEdge); +} + +/** + * @brief Stop ADC group regular conversion from external trigger. + * @note No more ADC conversion will start at next trigger event + * following the ADC stop conversion command. + * If a conversion is on-going, it will be completed. + * @note On this STM32 series, there is no specific command + * to stop a conversion on-going or to stop ADC converting + * in continuous mode. These actions can be performed + * using function @ref LL_ADC_Disable(). + * @rmtoll CR2 EXTEN LL_ADC_REG_StopConversionExtTrig + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_REG_StopConversionExtTrig(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR2, ADC_CR2_EXTEN); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * all ADC configurations: all ADC resolutions and + * all oversampling increased data width (for devices + * with feature oversampling). + * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData32 + * @param ADCx ADC instance + * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_ADC_REG_ReadConversionData32(ADC_TypeDef *ADCx) +{ + return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * ADC resolution 12 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_REG_ReadConversionData32. + * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData12 + * @param ADCx ADC instance + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData12(ADC_TypeDef *ADCx) +{ + return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * ADC resolution 10 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_REG_ReadConversionData32. + * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData10 + * @param ADCx ADC instance + * @retval Value between Min_Data=0x000 and Max_Data=0x3FF + */ +__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData10(ADC_TypeDef *ADCx) +{ + return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * ADC resolution 8 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_REG_ReadConversionData32. + * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData8 + * @param ADCx ADC instance + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData8(ADC_TypeDef *ADCx) +{ + return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * ADC resolution 6 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_REG_ReadConversionData32. + * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData6 + * @param ADCx ADC instance + * @retval Value between Min_Data=0x00 and Max_Data=0x3F + */ +__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData6(ADC_TypeDef *ADCx) +{ + return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); +} + +#if defined(ADC_MULTIMODE_SUPPORT) +/** + * @brief Get ADC multimode conversion data of ADC master, ADC slave + * or raw data with ADC master and slave concatenated. + * @note If raw data with ADC master and slave concatenated is retrieved, + * a macro is available to get the conversion data of + * ADC master or ADC slave: see helper macro + * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). + * (however this macro is mainly intended for multimode + * transfer by DMA, because this function can do the same + * by getting multimode conversion data of ADC master or ADC slave + * separately). + * @rmtoll CDR DATA1 LL_ADC_REG_ReadMultiConversionData32\n + * CDR DATA2 LL_ADC_REG_ReadMultiConversionData32 + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param ConversionData This parameter can be one of the following values: + * @arg @ref LL_ADC_MULTI_MASTER + * @arg @ref LL_ADC_MULTI_SLAVE + * @arg @ref LL_ADC_MULTI_MASTER_SLAVE + * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_ADC_REG_ReadMultiConversionData32(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t ConversionData) +{ + return (uint32_t)(READ_BIT(ADCxy_COMMON->CDR, + ADC_DR_ADC2DATA) + >> POSITION_VAL(ConversionData) + ); +} +#endif /* ADC_MULTIMODE_SUPPORT */ + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_Operation_ADC_Group_Injected Operation on ADC hierarchical scope: group injected + * @{ + */ + +/** + * @brief Start ADC group injected conversion. + * @note On this STM32 series, this function is relevant only for + * internal trigger (SW start), not for external trigger: + * - If ADC trigger has been set to software start, ADC conversion + * starts immediately. + * - If ADC trigger has been set to external trigger, ADC conversion + * start must be performed using function + * @ref LL_ADC_INJ_StartConversionExtTrig(). + * (if external trigger edge would have been set during ADC other + * settings, ADC conversion would start at trigger event + * as soon as ADC is enabled). + * @rmtoll CR2 JSWSTART LL_ADC_INJ_StartConversionSWStart + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_StartConversionSWStart(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR2, ADC_CR2_JSWSTART); +} + +/** + * @brief Start ADC group injected conversion from external trigger. + * @note ADC conversion will start at next trigger event (on the selected + * trigger edge) following the ADC start conversion command. + * @note On this STM32 series, this function is relevant for + * ADC conversion start from external trigger. + * If internal trigger (SW start) is needed, perform ADC conversion + * start using function @ref LL_ADC_INJ_StartConversionSWStart(). + * @rmtoll CR2 JEXTEN LL_ADC_INJ_StartConversionExtTrig + * @param ExternalTriggerEdge This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING + * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING + * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) +{ + SET_BIT(ADCx->CR2, ExternalTriggerEdge); +} + +/** + * @brief Stop ADC group injected conversion from external trigger. + * @note No more ADC conversion will start at next trigger event + * following the ADC stop conversion command. + * If a conversion is on-going, it will be completed. + * @note On this STM32 series, there is no specific command + * to stop a conversion on-going or to stop ADC converting + * in continuous mode. These actions can be performed + * using function @ref LL_ADC_Disable(). + * @rmtoll CR2 JEXTEN LL_ADC_INJ_StopConversionExtTrig + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_INJ_StopConversionExtTrig(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR2, ADC_CR2_JEXTEN); +} + +/** + * @brief Get ADC group regular conversion data, range fit for + * all ADC configurations: all ADC resolutions and + * all oversampling increased data width (for devices + * with feature oversampling). + * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData32\n + * JDR2 JDATA LL_ADC_INJ_ReadConversionData32\n + * JDR3 JDATA LL_ADC_INJ_ReadConversionData32\n + * JDR4 JDATA LL_ADC_INJ_ReadConversionData32 + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_ADC_INJ_ReadConversionData32(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); + + return (uint32_t)(READ_BIT(*preg, + ADC_JDR1_JDATA) + ); +} + +/** + * @brief Get ADC group injected conversion data, range fit for + * ADC resolution 12 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_INJ_ReadConversionData32. + * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData12\n + * JDR2 JDATA LL_ADC_INJ_ReadConversionData12\n + * JDR3 JDATA LL_ADC_INJ_ReadConversionData12\n + * JDR4 JDATA LL_ADC_INJ_ReadConversionData12 + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x000 and Max_Data=0xFFF + */ +__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData12(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); + + return (uint16_t)(READ_BIT(*preg, + ADC_JDR1_JDATA) + ); +} + +/** + * @brief Get ADC group injected conversion data, range fit for + * ADC resolution 10 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_INJ_ReadConversionData32. + * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData10\n + * JDR2 JDATA LL_ADC_INJ_ReadConversionData10\n + * JDR3 JDATA LL_ADC_INJ_ReadConversionData10\n + * JDR4 JDATA LL_ADC_INJ_ReadConversionData10 + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x000 and Max_Data=0x3FF + */ +__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData10(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); + + return (uint16_t)(READ_BIT(*preg, + ADC_JDR1_JDATA) + ); +} + +/** + * @brief Get ADC group injected conversion data, range fit for + * ADC resolution 8 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_INJ_ReadConversionData32. + * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData8\n + * JDR2 JDATA LL_ADC_INJ_ReadConversionData8\n + * JDR3 JDATA LL_ADC_INJ_ReadConversionData8\n + * JDR4 JDATA LL_ADC_INJ_ReadConversionData8 + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData8(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); + + return (uint8_t)(READ_BIT(*preg, + ADC_JDR1_JDATA) + ); +} + +/** + * @brief Get ADC group injected conversion data, range fit for + * ADC resolution 6 bits. + * @note For devices with feature oversampling: Oversampling + * can increase data width, function for extended range + * may be needed: @ref LL_ADC_INJ_ReadConversionData32. + * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData6\n + * JDR2 JDATA LL_ADC_INJ_ReadConversionData6\n + * JDR3 JDATA LL_ADC_INJ_ReadConversionData6\n + * JDR4 JDATA LL_ADC_INJ_ReadConversionData6 + * @param ADCx ADC instance + * @param Rank This parameter can be one of the following values: + * @arg @ref LL_ADC_INJ_RANK_1 + * @arg @ref LL_ADC_INJ_RANK_2 + * @arg @ref LL_ADC_INJ_RANK_3 + * @arg @ref LL_ADC_INJ_RANK_4 + * @retval Value between Min_Data=0x00 and Max_Data=0x3F + */ +__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData6(ADC_TypeDef *ADCx, uint32_t Rank) +{ + __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); + + return (uint8_t)(READ_BIT(*preg, + ADC_JDR1_JDATA) + ); +} + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_FLAG_Management ADC flag management + * @{ + */ + +/** + * @brief Get flag ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll SR EOC LL_ADC_IsActiveFlag_EOCS + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_EOCS(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); +} + +/** + * @brief Get flag ADC group regular overrun. + * @rmtoll SR OVR LL_ADC_IsActiveFlag_OVR + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_OVR(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->SR, LL_ADC_FLAG_OVR) == (LL_ADC_FLAG_OVR)); +} + + +/** + * @brief Get flag ADC group injected end of sequence conversions. + * @rmtoll SR JEOC LL_ADC_IsActiveFlag_JEOS + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_JEOS(ADC_TypeDef *ADCx) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + return (READ_BIT(ADCx->SR, LL_ADC_FLAG_JEOS) == (LL_ADC_FLAG_JEOS)); +} + +/** + * @brief Get flag ADC analog watchdog 1 flag + * @rmtoll SR AWD LL_ADC_IsActiveFlag_AWD1 + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_AWD1(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->SR, LL_ADC_FLAG_AWD1) == (LL_ADC_FLAG_AWD1)); +} + +/** + * @brief Clear flag ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll SR EOC LL_ADC_ClearFlag_EOCS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_ClearFlag_EOCS(ADC_TypeDef *ADCx) +{ + WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_EOCS); +} + +/** + * @brief Clear flag ADC group regular overrun. + * @rmtoll SR OVR LL_ADC_ClearFlag_OVR + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_ClearFlag_OVR(ADC_TypeDef *ADCx) +{ + WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_OVR); +} + + +/** + * @brief Clear flag ADC group injected end of sequence conversions. + * @rmtoll SR JEOC LL_ADC_ClearFlag_JEOS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_ClearFlag_JEOS(ADC_TypeDef *ADCx) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_JEOS); +} + +/** + * @brief Clear flag ADC analog watchdog 1. + * @rmtoll SR AWD LL_ADC_ClearFlag_AWD1 + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_ClearFlag_AWD1(ADC_TypeDef *ADCx) +{ + WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_AWD1); +} + +#if defined(ADC_MULTIMODE_SUPPORT) +/** + * @brief Get flag multimode ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration, of the ADC master. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll CSR EOC1 LL_ADC_IsActiveFlag_MST_EOCS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_MST) == (LL_ADC_FLAG_EOCS_MST)); +} + +/** + * @brief Get flag multimode ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration, of the ADC slave 1. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll CSR EOC2 LL_ADC_IsActiveFlag_SLV1_EOCS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV1) == (LL_ADC_FLAG_EOCS_SLV1)); +} + +/** + * @brief Get flag multimode ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration, of the ADC slave 2. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll CSR EOC3 LL_ADC_IsActiveFlag_SLV2_EOCS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV2) == (LL_ADC_FLAG_EOCS_SLV2)); +} +/** + * @brief Get flag multimode ADC group regular overrun of the ADC master. + * @rmtoll CSR OVR1 LL_ADC_IsActiveFlag_MST_OVR + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_OVR(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_MST) == (LL_ADC_FLAG_OVR_MST)); +} + +/** + * @brief Get flag multimode ADC group regular overrun of the ADC slave 1. + * @rmtoll CSR OVR2 LL_ADC_IsActiveFlag_SLV1_OVR + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_OVR(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV1) == (LL_ADC_FLAG_OVR_SLV1)); +} + +/** + * @brief Get flag multimode ADC group regular overrun of the ADC slave 2. + * @rmtoll CSR OVR3 LL_ADC_IsActiveFlag_SLV2_OVR + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_OVR(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV2) == (LL_ADC_FLAG_OVR_SLV2)); +} + + +/** + * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC master. + * @rmtoll CSR JEOC LL_ADC_IsActiveFlag_MST_JEOS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC1) == (ADC_CSR_JEOC1)); +} + +/** + * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 1. + * @rmtoll CSR JEOC2 LL_ADC_IsActiveFlag_SLV1_JEOS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC2) == (ADC_CSR_JEOC2)); +} + +/** + * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 2. + * @rmtoll CSR JEOC3 LL_ADC_IsActiveFlag_SLV2_JEOS + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC3) == (ADC_CSR_JEOC3)); +} + +/** + * @brief Get flag multimode ADC analog watchdog 1 of the ADC master. + * @rmtoll CSR AWD1 LL_ADC_IsActiveFlag_MST_AWD1 + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_MST) == (LL_ADC_FLAG_AWD1_MST)); +} + +/** + * @brief Get flag multimode analog watchdog 1 of the ADC slave 1. + * @rmtoll CSR AWD2 LL_ADC_IsActiveFlag_SLV1_AWD1 + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV1) == (LL_ADC_FLAG_AWD1_SLV1)); +} + +/** + * @brief Get flag multimode analog watchdog 1 of the ADC slave 2. + * @rmtoll CSR AWD3 LL_ADC_IsActiveFlag_SLV2_AWD1 + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) +{ + return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV2) == (LL_ADC_FLAG_AWD1_SLV2)); +} + +#endif /* ADC_MULTIMODE_SUPPORT */ + +/** + * @} + */ + +/** @defgroup ADC_LL_EF_IT_Management ADC IT management + * @{ + */ + +/** + * @brief Enable interruption ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll CR1 EOCIE LL_ADC_EnableIT_EOCS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_EnableIT_EOCS(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR1, LL_ADC_IT_EOCS); +} + +/** + * @brief Enable ADC group regular interruption overrun. + * @rmtoll CR1 OVRIE LL_ADC_EnableIT_OVR + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_EnableIT_OVR(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR1, LL_ADC_IT_OVR); +} + + +/** + * @brief Enable interruption ADC group injected end of sequence conversions. + * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_EnableIT_JEOS(ADC_TypeDef *ADCx) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + SET_BIT(ADCx->CR1, LL_ADC_IT_JEOS); +} + +/** + * @brief Enable interruption ADC analog watchdog 1. + * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_EnableIT_AWD1(ADC_TypeDef *ADCx) +{ + SET_BIT(ADCx->CR1, LL_ADC_IT_AWD1); +} + +/** + * @brief Disable interruption ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * @rmtoll CR1 EOCIE LL_ADC_DisableIT_EOCS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_DisableIT_EOCS(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR1, LL_ADC_IT_EOCS); +} + +/** + * @brief Disable interruption ADC group regular overrun. + * @rmtoll CR1 OVRIE LL_ADC_DisableIT_OVR + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_DisableIT_OVR(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR1, LL_ADC_IT_OVR); +} + + +/** + * @brief Disable interruption ADC group injected end of sequence conversions. + * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_DisableIT_JEOS(ADC_TypeDef *ADCx) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + CLEAR_BIT(ADCx->CR1, LL_ADC_IT_JEOS); +} + +/** + * @brief Disable interruption ADC analog watchdog 1. + * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 + * @param ADCx ADC instance + * @retval None + */ +__STATIC_INLINE void LL_ADC_DisableIT_AWD1(ADC_TypeDef *ADCx) +{ + CLEAR_BIT(ADCx->CR1, LL_ADC_IT_AWD1); +} + +/** + * @brief Get state of interruption ADC group regular end of unitary conversion + * or end of sequence conversions, depending on + * ADC configuration. + * @note To configure flag of end of conversion, + * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). + * (0: interrupt disabled, 1: interrupt enabled) + * @rmtoll CR1 EOCIE LL_ADC_IsEnabledIT_EOCS + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_EOCS(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR1, LL_ADC_IT_EOCS) == (LL_ADC_IT_EOCS)); +} + +/** + * @brief Get state of interruption ADC group regular overrun + * (0: interrupt disabled, 1: interrupt enabled). + * @rmtoll CR1 OVRIE LL_ADC_IsEnabledIT_OVR + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_OVR(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR1, LL_ADC_IT_OVR) == (LL_ADC_IT_OVR)); +} + + +/** + * @brief Get state of interruption ADC group injected end of sequence conversions + * (0: interrupt disabled, 1: interrupt enabled). + * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_JEOS(ADC_TypeDef *ADCx) +{ + /* Note: on this STM32 series, there is no flag ADC group injected */ + /* end of unitary conversion. */ + /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ + /* in other STM32 families). */ + return (READ_BIT(ADCx->CR1, LL_ADC_IT_JEOS) == (LL_ADC_IT_JEOS)); +} + +/** + * @brief Get state of interruption ADC analog watchdog 1 + * (0: interrupt disabled, 1: interrupt enabled). + * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 + * @param ADCx ADC instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_AWD1(ADC_TypeDef *ADCx) +{ + return (READ_BIT(ADCx->CR1, LL_ADC_IT_AWD1) == (LL_ADC_IT_AWD1)); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup ADC_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +/* Initialization of some features of ADC common parameters and multimode */ +ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON); +ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); +void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); + +/* De-initialization of ADC instance, ADC group regular and ADC group injected */ +/* (availability of ADC group injected depends on STM32 families) */ +ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx); + +/* Initialization of some features of ADC instance */ +ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct); +void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct); + +/* Initialization of some features of ADC instance and ADC group regular */ +ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); +void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); + +/* Initialization of some features of ADC instance and ADC group injected */ +ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); +void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* ADC1 || ADC2 || ADC3 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_ADC_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h index 5083c10..460edfc 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h @@ -1,2105 +1,2105 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_bus.h - * @author MCD Application Team - * @brief Header file of BUS LL module. - - @verbatim - ##### RCC Limitations ##### - ============================================================================== - [..] - A delay between an RCC peripheral clock enable and the effective peripheral - enabling should be taken into account in order to manage the peripheral read/write - from/to registers. - (+) This delay depends on the peripheral mapping. - (++) AHB & APB peripherals, 1 dummy read is necessary - - [..] - Workarounds: - (#) For AHB & APB peripherals, a dummy read to the peripheral register has been - inserted in each LL_{BUS}_GRP{x}_EnableClock() function. - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_BUS_H -#define __STM32F4xx_LL_BUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup BUS_LL BUS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Constants BUS Exported Constants - * @{ - */ - -/** @defgroup BUS_LL_EC_AHB1_GRP1_PERIPH AHB1 GRP1 PERIPH - * @{ - */ -#define LL_AHB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_AHB1_GRP1_PERIPH_GPIOA RCC_AHB1ENR_GPIOAEN -#define LL_AHB1_GRP1_PERIPH_GPIOB RCC_AHB1ENR_GPIOBEN -#define LL_AHB1_GRP1_PERIPH_GPIOC RCC_AHB1ENR_GPIOCEN -#if defined(GPIOD) -#define LL_AHB1_GRP1_PERIPH_GPIOD RCC_AHB1ENR_GPIODEN -#endif /* GPIOD */ -#if defined(GPIOE) -#define LL_AHB1_GRP1_PERIPH_GPIOE RCC_AHB1ENR_GPIOEEN -#endif /* GPIOE */ -#if defined(GPIOF) -#define LL_AHB1_GRP1_PERIPH_GPIOF RCC_AHB1ENR_GPIOFEN -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_AHB1_GRP1_PERIPH_GPIOG RCC_AHB1ENR_GPIOGEN -#endif /* GPIOG */ -#if defined(GPIOH) -#define LL_AHB1_GRP1_PERIPH_GPIOH RCC_AHB1ENR_GPIOHEN -#endif /* GPIOH */ -#if defined(GPIOI) -#define LL_AHB1_GRP1_PERIPH_GPIOI RCC_AHB1ENR_GPIOIEN -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_AHB1_GRP1_PERIPH_GPIOJ RCC_AHB1ENR_GPIOJEN -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_AHB1_GRP1_PERIPH_GPIOK RCC_AHB1ENR_GPIOKEN -#endif /* GPIOK */ -#define LL_AHB1_GRP1_PERIPH_CRC RCC_AHB1ENR_CRCEN -#if defined(RCC_AHB1ENR_BKPSRAMEN) -#define LL_AHB1_GRP1_PERIPH_BKPSRAM RCC_AHB1ENR_BKPSRAMEN -#endif /* RCC_AHB1ENR_BKPSRAMEN */ -#if defined(RCC_AHB1ENR_CCMDATARAMEN) -#define LL_AHB1_GRP1_PERIPH_CCMDATARAM RCC_AHB1ENR_CCMDATARAMEN -#endif /* RCC_AHB1ENR_CCMDATARAMEN */ -#define LL_AHB1_GRP1_PERIPH_DMA1 RCC_AHB1ENR_DMA1EN -#define LL_AHB1_GRP1_PERIPH_DMA2 RCC_AHB1ENR_DMA2EN -#if defined(RCC_AHB1ENR_RNGEN) -#define LL_AHB1_GRP1_PERIPH_RNG RCC_AHB1ENR_RNGEN -#endif /* RCC_AHB1ENR_RNGEN */ -#if defined(DMA2D) -#define LL_AHB1_GRP1_PERIPH_DMA2D RCC_AHB1ENR_DMA2DEN -#endif /* DMA2D */ -#if defined(ETH) -#define LL_AHB1_GRP1_PERIPH_ETHMAC RCC_AHB1ENR_ETHMACEN -#define LL_AHB1_GRP1_PERIPH_ETHMACTX RCC_AHB1ENR_ETHMACTXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACRX RCC_AHB1ENR_ETHMACRXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACPTP RCC_AHB1ENR_ETHMACPTPEN -#endif /* ETH */ -#if defined(USB_OTG_HS) -#define LL_AHB1_GRP1_PERIPH_OTGHS RCC_AHB1ENR_OTGHSEN -#define LL_AHB1_GRP1_PERIPH_OTGHSULPI RCC_AHB1ENR_OTGHSULPIEN -#endif /* USB_OTG_HS */ -#define LL_AHB1_GRP1_PERIPH_FLITF RCC_AHB1LPENR_FLITFLPEN -#define LL_AHB1_GRP1_PERIPH_SRAM1 RCC_AHB1LPENR_SRAM1LPEN -#if defined(RCC_AHB1LPENR_SRAM2LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM2 RCC_AHB1LPENR_SRAM2LPEN -#endif /* RCC_AHB1LPENR_SRAM2LPEN */ -#if defined(RCC_AHB1LPENR_SRAM3LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM3 RCC_AHB1LPENR_SRAM3LPEN -#endif /* RCC_AHB1LPENR_SRAM3LPEN */ -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EC_AHB2_GRP1_PERIPH AHB2 GRP1 PERIPH - * @{ - */ -#define LL_AHB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(DCMI) -#define LL_AHB2_GRP1_PERIPH_DCMI RCC_AHB2ENR_DCMIEN -#endif /* DCMI */ -#if defined(CRYP) -#define LL_AHB2_GRP1_PERIPH_CRYP RCC_AHB2ENR_CRYPEN -#endif /* CRYP */ -#if defined(AES) -#define LL_AHB2_GRP1_PERIPH_AES RCC_AHB2ENR_AESEN -#endif /* AES */ -#if defined(HASH) -#define LL_AHB2_GRP1_PERIPH_HASH RCC_AHB2ENR_HASHEN -#endif /* HASH */ -#if defined(RCC_AHB2ENR_RNGEN) -#define LL_AHB2_GRP1_PERIPH_RNG RCC_AHB2ENR_RNGEN -#endif /* RCC_AHB2ENR_RNGEN */ -#if defined(USB_OTG_FS) -#define LL_AHB2_GRP1_PERIPH_OTGFS RCC_AHB2ENR_OTGFSEN -#endif /* USB_OTG_FS */ -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EC_AHB3_GRP1_PERIPH AHB3 GRP1 PERIPH - * @{ - */ -#define LL_AHB3_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(FSMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FSMC RCC_AHB3ENR_FSMCEN -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FMC RCC_AHB3ENR_FMCEN -#endif /* FMC_Bank1 */ -#if defined(QUADSPI) -#define LL_AHB3_GRP1_PERIPH_QSPI RCC_AHB3ENR_QSPIEN -#endif /* QUADSPI */ -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EC_APB1_GRP1_PERIPH APB1 GRP1 PERIPH - * @{ - */ -#define LL_APB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(TIM2) -#define LL_APB1_GRP1_PERIPH_TIM2 RCC_APB1ENR_TIM2EN -#endif /* TIM2 */ -#if defined(TIM3) -#define LL_APB1_GRP1_PERIPH_TIM3 RCC_APB1ENR_TIM3EN -#endif /* TIM3 */ -#if defined(TIM4) -#define LL_APB1_GRP1_PERIPH_TIM4 RCC_APB1ENR_TIM4EN -#endif /* TIM4 */ -#define LL_APB1_GRP1_PERIPH_TIM5 RCC_APB1ENR_TIM5EN -#if defined(TIM6) -#define LL_APB1_GRP1_PERIPH_TIM6 RCC_APB1ENR_TIM6EN -#endif /* TIM6 */ -#if defined(TIM7) -#define LL_APB1_GRP1_PERIPH_TIM7 RCC_APB1ENR_TIM7EN -#endif /* TIM7 */ -#if defined(TIM12) -#define LL_APB1_GRP1_PERIPH_TIM12 RCC_APB1ENR_TIM12EN -#endif /* TIM12 */ -#if defined(TIM13) -#define LL_APB1_GRP1_PERIPH_TIM13 RCC_APB1ENR_TIM13EN -#endif /* TIM13 */ -#if defined(TIM14) -#define LL_APB1_GRP1_PERIPH_TIM14 RCC_APB1ENR_TIM14EN -#endif /* TIM14 */ -#if defined(LPTIM1) -#define LL_APB1_GRP1_PERIPH_LPTIM1 RCC_APB1ENR_LPTIM1EN -#endif /* LPTIM1 */ -#if defined(RCC_APB1ENR_RTCAPBEN) -#define LL_APB1_GRP1_PERIPH_RTCAPB RCC_APB1ENR_RTCAPBEN -#endif /* RCC_APB1ENR_RTCAPBEN */ -#define LL_APB1_GRP1_PERIPH_WWDG RCC_APB1ENR_WWDGEN -#if defined(SPI2) -#define LL_APB1_GRP1_PERIPH_SPI2 RCC_APB1ENR_SPI2EN -#endif /* SPI2 */ -#if defined(SPI3) -#define LL_APB1_GRP1_PERIPH_SPI3 RCC_APB1ENR_SPI3EN -#endif /* SPI3 */ -#if defined(SPDIFRX) -#define LL_APB1_GRP1_PERIPH_SPDIFRX RCC_APB1ENR_SPDIFRXEN -#endif /* SPDIFRX */ -#define LL_APB1_GRP1_PERIPH_USART2 RCC_APB1ENR_USART2EN -#if defined(USART3) -#define LL_APB1_GRP1_PERIPH_USART3 RCC_APB1ENR_USART3EN -#endif /* USART3 */ -#if defined(UART4) -#define LL_APB1_GRP1_PERIPH_UART4 RCC_APB1ENR_UART4EN -#endif /* UART4 */ -#if defined(UART5) -#define LL_APB1_GRP1_PERIPH_UART5 RCC_APB1ENR_UART5EN -#endif /* UART5 */ -#define LL_APB1_GRP1_PERIPH_I2C1 RCC_APB1ENR_I2C1EN -#define LL_APB1_GRP1_PERIPH_I2C2 RCC_APB1ENR_I2C2EN -#if defined(I2C3) -#define LL_APB1_GRP1_PERIPH_I2C3 RCC_APB1ENR_I2C3EN -#endif /* I2C3 */ -#if defined(FMPI2C1) -#define LL_APB1_GRP1_PERIPH_FMPI2C1 RCC_APB1ENR_FMPI2C1EN -#endif /* FMPI2C1 */ -#if defined(CAN1) -#define LL_APB1_GRP1_PERIPH_CAN1 RCC_APB1ENR_CAN1EN -#endif /* CAN1 */ -#if defined(CAN2) -#define LL_APB1_GRP1_PERIPH_CAN2 RCC_APB1ENR_CAN2EN -#endif /* CAN2 */ -#if defined(CAN3) -#define LL_APB1_GRP1_PERIPH_CAN3 RCC_APB1ENR_CAN3EN -#endif /* CAN3 */ -#if defined(CEC) -#define LL_APB1_GRP1_PERIPH_CEC RCC_APB1ENR_CECEN -#endif /* CEC */ -#define LL_APB1_GRP1_PERIPH_PWR RCC_APB1ENR_PWREN -#if defined(DAC1) -#define LL_APB1_GRP1_PERIPH_DAC1 RCC_APB1ENR_DACEN -#endif /* DAC1 */ -#if defined(UART7) -#define LL_APB1_GRP1_PERIPH_UART7 RCC_APB1ENR_UART7EN -#endif /* UART7 */ -#if defined(UART8) -#define LL_APB1_GRP1_PERIPH_UART8 RCC_APB1ENR_UART8EN -#endif /* UART8 */ -/** - * @} - */ - -/** @defgroup BUS_LL_EC_APB2_GRP1_PERIPH APB2 GRP1 PERIPH - * @{ - */ -#define LL_APB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_APB2_GRP1_PERIPH_TIM1 RCC_APB2ENR_TIM1EN -#if defined(TIM8) -#define LL_APB2_GRP1_PERIPH_TIM8 RCC_APB2ENR_TIM8EN -#endif /* TIM8 */ -#define LL_APB2_GRP1_PERIPH_USART1 RCC_APB2ENR_USART1EN -#if defined(USART6) -#define LL_APB2_GRP1_PERIPH_USART6 RCC_APB2ENR_USART6EN -#endif /* USART6 */ -#if defined(UART9) -#define LL_APB2_GRP1_PERIPH_UART9 RCC_APB2ENR_UART9EN -#endif /* UART9 */ -#if defined(UART10) -#define LL_APB2_GRP1_PERIPH_UART10 RCC_APB2ENR_UART10EN -#endif /* UART10 */ -#define LL_APB2_GRP1_PERIPH_ADC1 RCC_APB2ENR_ADC1EN -#if defined(ADC2) -#define LL_APB2_GRP1_PERIPH_ADC2 RCC_APB2ENR_ADC2EN -#endif /* ADC2 */ -#if defined(ADC3) -#define LL_APB2_GRP1_PERIPH_ADC3 RCC_APB2ENR_ADC3EN -#endif /* ADC3 */ -#if defined(SDIO) -#define LL_APB2_GRP1_PERIPH_SDIO RCC_APB2ENR_SDIOEN -#endif /* SDIO */ -#define LL_APB2_GRP1_PERIPH_SPI1 RCC_APB2ENR_SPI1EN -#if defined(SPI4) -#define LL_APB2_GRP1_PERIPH_SPI4 RCC_APB2ENR_SPI4EN -#endif /* SPI4 */ -#define LL_APB2_GRP1_PERIPH_SYSCFG RCC_APB2ENR_SYSCFGEN -#if defined(RCC_APB2ENR_EXTITEN) -#define LL_APB2_GRP1_PERIPH_EXTI RCC_APB2ENR_EXTITEN -#endif /* RCC_APB2ENR_EXTITEN */ -#define LL_APB2_GRP1_PERIPH_TIM9 RCC_APB2ENR_TIM9EN -#if defined(TIM10) -#define LL_APB2_GRP1_PERIPH_TIM10 RCC_APB2ENR_TIM10EN -#endif /* TIM10 */ -#define LL_APB2_GRP1_PERIPH_TIM11 RCC_APB2ENR_TIM11EN -#if defined(SPI5) -#define LL_APB2_GRP1_PERIPH_SPI5 RCC_APB2ENR_SPI5EN -#endif /* SPI5 */ -#if defined(SPI6) -#define LL_APB2_GRP1_PERIPH_SPI6 RCC_APB2ENR_SPI6EN -#endif /* SPI6 */ -#if defined(SAI1) -#define LL_APB2_GRP1_PERIPH_SAI1 RCC_APB2ENR_SAI1EN -#endif /* SAI1 */ -#if defined(SAI2) -#define LL_APB2_GRP1_PERIPH_SAI2 RCC_APB2ENR_SAI2EN -#endif /* SAI2 */ -#if defined(LTDC) -#define LL_APB2_GRP1_PERIPH_LTDC RCC_APB2ENR_LTDCEN -#endif /* LTDC */ -#if defined(DSI) -#define LL_APB2_GRP1_PERIPH_DSI RCC_APB2ENR_DSIEN -#endif /* DSI */ -#if defined(DFSDM1_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM1 RCC_APB2ENR_DFSDM1EN -#endif /* DFSDM1_Channel0 */ -#if defined(DFSDM2_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM2 RCC_APB2ENR_DFSDM2EN -#endif /* DFSDM2_Channel0 */ -#define LL_APB2_GRP1_PERIPH_ADC RCC_APB2RSTR_ADCRST -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Functions BUS Exported Functions - * @{ - */ - -/** @defgroup BUS_LL_EF_AHB1 AHB1 - * @{ - */ - -/** - * @brief Enable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB1 peripheral clock is enabled or not - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1ENR, Periphs); -} - -/** - * @brief Force AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Release AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Enable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1LPENR, Periphs); -} - -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EF_AHB2 AHB2 - * @{ - */ - -/** - * @brief Enable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB2 peripheral clock is enabled or not - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2ENR, Periphs); -} - -/** - * @brief Force AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Release AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Enable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EF_AHB3 AHB3 - * @{ - */ - -/** - * @brief Enable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB3 peripheral clock is enabled or not - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB3_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB3ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3ENR, Periphs); -} - -/** - * @brief Force AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Release AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Enable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EF_APB1 APB1 - * @{ - */ - -/** - * @brief Enable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_EnableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CECEN LL_APB1_GRP1_EnableClock\n - * APB1ENR PWREN LL_APB1_GRP1_EnableClock\n - * APB1ENR DACEN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_EnableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB1 peripheral clock is enabled or not - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CECEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR PWREN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR DACEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART8EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_DisableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CECEN LL_APB1_GRP1_DisableClock\n - * APB1ENR PWREN LL_APB1_GRP1_DisableClock\n - * APB1ENR DACEN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_DisableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1ENR, Periphs); -} - -/** - * @brief Force APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Release APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Enable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1LPENR, Periphs); -} - -/** - * @} - */ - -/** @defgroup BUS_LL_EF_APB2 APB2 - * @{ - */ - -/** - * @brief Enable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_EnableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB2 peripheral clock is enabled or not - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DSIEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_DisableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2ENR, Periphs); -} - -/** - * @brief Force APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Release APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Enable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2LPENR, Periphs); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_BUS_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_bus.h + * @author MCD Application Team + * @brief Header file of BUS LL module. + + @verbatim + ##### RCC Limitations ##### + ============================================================================== + [..] + A delay between an RCC peripheral clock enable and the effective peripheral + enabling should be taken into account in order to manage the peripheral read/write + from/to registers. + (+) This delay depends on the peripheral mapping. + (++) AHB & APB peripherals, 1 dummy read is necessary + + [..] + Workarounds: + (#) For AHB & APB peripherals, a dummy read to the peripheral register has been + inserted in each LL_{BUS}_GRP{x}_EnableClock() function. + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_BUS_H +#define __STM32F4xx_LL_BUS_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(RCC) + +/** @defgroup BUS_LL BUS + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup BUS_LL_Exported_Constants BUS Exported Constants + * @{ + */ + +/** @defgroup BUS_LL_EC_AHB1_GRP1_PERIPH AHB1 GRP1 PERIPH + * @{ + */ +#define LL_AHB1_GRP1_PERIPH_ALL 0xFFFFFFFFU +#define LL_AHB1_GRP1_PERIPH_GPIOA RCC_AHB1ENR_GPIOAEN +#define LL_AHB1_GRP1_PERIPH_GPIOB RCC_AHB1ENR_GPIOBEN +#define LL_AHB1_GRP1_PERIPH_GPIOC RCC_AHB1ENR_GPIOCEN +#if defined(GPIOD) +#define LL_AHB1_GRP1_PERIPH_GPIOD RCC_AHB1ENR_GPIODEN +#endif /* GPIOD */ +#if defined(GPIOE) +#define LL_AHB1_GRP1_PERIPH_GPIOE RCC_AHB1ENR_GPIOEEN +#endif /* GPIOE */ +#if defined(GPIOF) +#define LL_AHB1_GRP1_PERIPH_GPIOF RCC_AHB1ENR_GPIOFEN +#endif /* GPIOF */ +#if defined(GPIOG) +#define LL_AHB1_GRP1_PERIPH_GPIOG RCC_AHB1ENR_GPIOGEN +#endif /* GPIOG */ +#if defined(GPIOH) +#define LL_AHB1_GRP1_PERIPH_GPIOH RCC_AHB1ENR_GPIOHEN +#endif /* GPIOH */ +#if defined(GPIOI) +#define LL_AHB1_GRP1_PERIPH_GPIOI RCC_AHB1ENR_GPIOIEN +#endif /* GPIOI */ +#if defined(GPIOJ) +#define LL_AHB1_GRP1_PERIPH_GPIOJ RCC_AHB1ENR_GPIOJEN +#endif /* GPIOJ */ +#if defined(GPIOK) +#define LL_AHB1_GRP1_PERIPH_GPIOK RCC_AHB1ENR_GPIOKEN +#endif /* GPIOK */ +#define LL_AHB1_GRP1_PERIPH_CRC RCC_AHB1ENR_CRCEN +#if defined(RCC_AHB1ENR_BKPSRAMEN) +#define LL_AHB1_GRP1_PERIPH_BKPSRAM RCC_AHB1ENR_BKPSRAMEN +#endif /* RCC_AHB1ENR_BKPSRAMEN */ +#if defined(RCC_AHB1ENR_CCMDATARAMEN) +#define LL_AHB1_GRP1_PERIPH_CCMDATARAM RCC_AHB1ENR_CCMDATARAMEN +#endif /* RCC_AHB1ENR_CCMDATARAMEN */ +#define LL_AHB1_GRP1_PERIPH_DMA1 RCC_AHB1ENR_DMA1EN +#define LL_AHB1_GRP1_PERIPH_DMA2 RCC_AHB1ENR_DMA2EN +#if defined(RCC_AHB1ENR_RNGEN) +#define LL_AHB1_GRP1_PERIPH_RNG RCC_AHB1ENR_RNGEN +#endif /* RCC_AHB1ENR_RNGEN */ +#if defined(DMA2D) +#define LL_AHB1_GRP1_PERIPH_DMA2D RCC_AHB1ENR_DMA2DEN +#endif /* DMA2D */ +#if defined(ETH) +#define LL_AHB1_GRP1_PERIPH_ETHMAC RCC_AHB1ENR_ETHMACEN +#define LL_AHB1_GRP1_PERIPH_ETHMACTX RCC_AHB1ENR_ETHMACTXEN +#define LL_AHB1_GRP1_PERIPH_ETHMACRX RCC_AHB1ENR_ETHMACRXEN +#define LL_AHB1_GRP1_PERIPH_ETHMACPTP RCC_AHB1ENR_ETHMACPTPEN +#endif /* ETH */ +#if defined(USB_OTG_HS) +#define LL_AHB1_GRP1_PERIPH_OTGHS RCC_AHB1ENR_OTGHSEN +#define LL_AHB1_GRP1_PERIPH_OTGHSULPI RCC_AHB1ENR_OTGHSULPIEN +#endif /* USB_OTG_HS */ +#define LL_AHB1_GRP1_PERIPH_FLITF RCC_AHB1LPENR_FLITFLPEN +#define LL_AHB1_GRP1_PERIPH_SRAM1 RCC_AHB1LPENR_SRAM1LPEN +#if defined(RCC_AHB1LPENR_SRAM2LPEN) +#define LL_AHB1_GRP1_PERIPH_SRAM2 RCC_AHB1LPENR_SRAM2LPEN +#endif /* RCC_AHB1LPENR_SRAM2LPEN */ +#if defined(RCC_AHB1LPENR_SRAM3LPEN) +#define LL_AHB1_GRP1_PERIPH_SRAM3 RCC_AHB1LPENR_SRAM3LPEN +#endif /* RCC_AHB1LPENR_SRAM3LPEN */ +/** + * @} + */ + +#if defined(RCC_AHB2_SUPPORT) +/** @defgroup BUS_LL_EC_AHB2_GRP1_PERIPH AHB2 GRP1 PERIPH + * @{ + */ +#define LL_AHB2_GRP1_PERIPH_ALL 0xFFFFFFFFU +#if defined(DCMI) +#define LL_AHB2_GRP1_PERIPH_DCMI RCC_AHB2ENR_DCMIEN +#endif /* DCMI */ +#if defined(CRYP) +#define LL_AHB2_GRP1_PERIPH_CRYP RCC_AHB2ENR_CRYPEN +#endif /* CRYP */ +#if defined(AES) +#define LL_AHB2_GRP1_PERIPH_AES RCC_AHB2ENR_AESEN +#endif /* AES */ +#if defined(HASH) +#define LL_AHB2_GRP1_PERIPH_HASH RCC_AHB2ENR_HASHEN +#endif /* HASH */ +#if defined(RCC_AHB2ENR_RNGEN) +#define LL_AHB2_GRP1_PERIPH_RNG RCC_AHB2ENR_RNGEN +#endif /* RCC_AHB2ENR_RNGEN */ +#if defined(USB_OTG_FS) +#define LL_AHB2_GRP1_PERIPH_OTGFS RCC_AHB2ENR_OTGFSEN +#endif /* USB_OTG_FS */ +/** + * @} + */ +#endif /* RCC_AHB2_SUPPORT */ + +#if defined(RCC_AHB3_SUPPORT) +/** @defgroup BUS_LL_EC_AHB3_GRP1_PERIPH AHB3 GRP1 PERIPH + * @{ + */ +#define LL_AHB3_GRP1_PERIPH_ALL 0xFFFFFFFFU +#if defined(FSMC_Bank1) +#define LL_AHB3_GRP1_PERIPH_FSMC RCC_AHB3ENR_FSMCEN +#endif /* FSMC_Bank1 */ +#if defined(FMC_Bank1) +#define LL_AHB3_GRP1_PERIPH_FMC RCC_AHB3ENR_FMCEN +#endif /* FMC_Bank1 */ +#if defined(QUADSPI) +#define LL_AHB3_GRP1_PERIPH_QSPI RCC_AHB3ENR_QSPIEN +#endif /* QUADSPI */ +/** + * @} + */ +#endif /* RCC_AHB3_SUPPORT */ + +/** @defgroup BUS_LL_EC_APB1_GRP1_PERIPH APB1 GRP1 PERIPH + * @{ + */ +#define LL_APB1_GRP1_PERIPH_ALL 0xFFFFFFFFU +#if defined(TIM2) +#define LL_APB1_GRP1_PERIPH_TIM2 RCC_APB1ENR_TIM2EN +#endif /* TIM2 */ +#if defined(TIM3) +#define LL_APB1_GRP1_PERIPH_TIM3 RCC_APB1ENR_TIM3EN +#endif /* TIM3 */ +#if defined(TIM4) +#define LL_APB1_GRP1_PERIPH_TIM4 RCC_APB1ENR_TIM4EN +#endif /* TIM4 */ +#define LL_APB1_GRP1_PERIPH_TIM5 RCC_APB1ENR_TIM5EN +#if defined(TIM6) +#define LL_APB1_GRP1_PERIPH_TIM6 RCC_APB1ENR_TIM6EN +#endif /* TIM6 */ +#if defined(TIM7) +#define LL_APB1_GRP1_PERIPH_TIM7 RCC_APB1ENR_TIM7EN +#endif /* TIM7 */ +#if defined(TIM12) +#define LL_APB1_GRP1_PERIPH_TIM12 RCC_APB1ENR_TIM12EN +#endif /* TIM12 */ +#if defined(TIM13) +#define LL_APB1_GRP1_PERIPH_TIM13 RCC_APB1ENR_TIM13EN +#endif /* TIM13 */ +#if defined(TIM14) +#define LL_APB1_GRP1_PERIPH_TIM14 RCC_APB1ENR_TIM14EN +#endif /* TIM14 */ +#if defined(LPTIM1) +#define LL_APB1_GRP1_PERIPH_LPTIM1 RCC_APB1ENR_LPTIM1EN +#endif /* LPTIM1 */ +#if defined(RCC_APB1ENR_RTCAPBEN) +#define LL_APB1_GRP1_PERIPH_RTCAPB RCC_APB1ENR_RTCAPBEN +#endif /* RCC_APB1ENR_RTCAPBEN */ +#define LL_APB1_GRP1_PERIPH_WWDG RCC_APB1ENR_WWDGEN +#if defined(SPI2) +#define LL_APB1_GRP1_PERIPH_SPI2 RCC_APB1ENR_SPI2EN +#endif /* SPI2 */ +#if defined(SPI3) +#define LL_APB1_GRP1_PERIPH_SPI3 RCC_APB1ENR_SPI3EN +#endif /* SPI3 */ +#if defined(SPDIFRX) +#define LL_APB1_GRP1_PERIPH_SPDIFRX RCC_APB1ENR_SPDIFRXEN +#endif /* SPDIFRX */ +#define LL_APB1_GRP1_PERIPH_USART2 RCC_APB1ENR_USART2EN +#if defined(USART3) +#define LL_APB1_GRP1_PERIPH_USART3 RCC_APB1ENR_USART3EN +#endif /* USART3 */ +#if defined(UART4) +#define LL_APB1_GRP1_PERIPH_UART4 RCC_APB1ENR_UART4EN +#endif /* UART4 */ +#if defined(UART5) +#define LL_APB1_GRP1_PERIPH_UART5 RCC_APB1ENR_UART5EN +#endif /* UART5 */ +#define LL_APB1_GRP1_PERIPH_I2C1 RCC_APB1ENR_I2C1EN +#define LL_APB1_GRP1_PERIPH_I2C2 RCC_APB1ENR_I2C2EN +#if defined(I2C3) +#define LL_APB1_GRP1_PERIPH_I2C3 RCC_APB1ENR_I2C3EN +#endif /* I2C3 */ +#if defined(FMPI2C1) +#define LL_APB1_GRP1_PERIPH_FMPI2C1 RCC_APB1ENR_FMPI2C1EN +#endif /* FMPI2C1 */ +#if defined(CAN1) +#define LL_APB1_GRP1_PERIPH_CAN1 RCC_APB1ENR_CAN1EN +#endif /* CAN1 */ +#if defined(CAN2) +#define LL_APB1_GRP1_PERIPH_CAN2 RCC_APB1ENR_CAN2EN +#endif /* CAN2 */ +#if defined(CAN3) +#define LL_APB1_GRP1_PERIPH_CAN3 RCC_APB1ENR_CAN3EN +#endif /* CAN3 */ +#if defined(CEC) +#define LL_APB1_GRP1_PERIPH_CEC RCC_APB1ENR_CECEN +#endif /* CEC */ +#define LL_APB1_GRP1_PERIPH_PWR RCC_APB1ENR_PWREN +#if defined(DAC1) +#define LL_APB1_GRP1_PERIPH_DAC1 RCC_APB1ENR_DACEN +#endif /* DAC1 */ +#if defined(UART7) +#define LL_APB1_GRP1_PERIPH_UART7 RCC_APB1ENR_UART7EN +#endif /* UART7 */ +#if defined(UART8) +#define LL_APB1_GRP1_PERIPH_UART8 RCC_APB1ENR_UART8EN +#endif /* UART8 */ +/** + * @} + */ + +/** @defgroup BUS_LL_EC_APB2_GRP1_PERIPH APB2 GRP1 PERIPH + * @{ + */ +#define LL_APB2_GRP1_PERIPH_ALL 0xFFFFFFFFU +#define LL_APB2_GRP1_PERIPH_TIM1 RCC_APB2ENR_TIM1EN +#if defined(TIM8) +#define LL_APB2_GRP1_PERIPH_TIM8 RCC_APB2ENR_TIM8EN +#endif /* TIM8 */ +#define LL_APB2_GRP1_PERIPH_USART1 RCC_APB2ENR_USART1EN +#if defined(USART6) +#define LL_APB2_GRP1_PERIPH_USART6 RCC_APB2ENR_USART6EN +#endif /* USART6 */ +#if defined(UART9) +#define LL_APB2_GRP1_PERIPH_UART9 RCC_APB2ENR_UART9EN +#endif /* UART9 */ +#if defined(UART10) +#define LL_APB2_GRP1_PERIPH_UART10 RCC_APB2ENR_UART10EN +#endif /* UART10 */ +#define LL_APB2_GRP1_PERIPH_ADC1 RCC_APB2ENR_ADC1EN +#if defined(ADC2) +#define LL_APB2_GRP1_PERIPH_ADC2 RCC_APB2ENR_ADC2EN +#endif /* ADC2 */ +#if defined(ADC3) +#define LL_APB2_GRP1_PERIPH_ADC3 RCC_APB2ENR_ADC3EN +#endif /* ADC3 */ +#if defined(SDIO) +#define LL_APB2_GRP1_PERIPH_SDIO RCC_APB2ENR_SDIOEN +#endif /* SDIO */ +#define LL_APB2_GRP1_PERIPH_SPI1 RCC_APB2ENR_SPI1EN +#if defined(SPI4) +#define LL_APB2_GRP1_PERIPH_SPI4 RCC_APB2ENR_SPI4EN +#endif /* SPI4 */ +#define LL_APB2_GRP1_PERIPH_SYSCFG RCC_APB2ENR_SYSCFGEN +#if defined(RCC_APB2ENR_EXTITEN) +#define LL_APB2_GRP1_PERIPH_EXTI RCC_APB2ENR_EXTITEN +#endif /* RCC_APB2ENR_EXTITEN */ +#define LL_APB2_GRP1_PERIPH_TIM9 RCC_APB2ENR_TIM9EN +#if defined(TIM10) +#define LL_APB2_GRP1_PERIPH_TIM10 RCC_APB2ENR_TIM10EN +#endif /* TIM10 */ +#define LL_APB2_GRP1_PERIPH_TIM11 RCC_APB2ENR_TIM11EN +#if defined(SPI5) +#define LL_APB2_GRP1_PERIPH_SPI5 RCC_APB2ENR_SPI5EN +#endif /* SPI5 */ +#if defined(SPI6) +#define LL_APB2_GRP1_PERIPH_SPI6 RCC_APB2ENR_SPI6EN +#endif /* SPI6 */ +#if defined(SAI1) +#define LL_APB2_GRP1_PERIPH_SAI1 RCC_APB2ENR_SAI1EN +#endif /* SAI1 */ +#if defined(SAI2) +#define LL_APB2_GRP1_PERIPH_SAI2 RCC_APB2ENR_SAI2EN +#endif /* SAI2 */ +#if defined(LTDC) +#define LL_APB2_GRP1_PERIPH_LTDC RCC_APB2ENR_LTDCEN +#endif /* LTDC */ +#if defined(DSI) +#define LL_APB2_GRP1_PERIPH_DSI RCC_APB2ENR_DSIEN +#endif /* DSI */ +#if defined(DFSDM1_Channel0) +#define LL_APB2_GRP1_PERIPH_DFSDM1 RCC_APB2ENR_DFSDM1EN +#endif /* DFSDM1_Channel0 */ +#if defined(DFSDM2_Channel0) +#define LL_APB2_GRP1_PERIPH_DFSDM2 RCC_APB2ENR_DFSDM2EN +#endif /* DFSDM2_Channel0 */ +#define LL_APB2_GRP1_PERIPH_ADC RCC_APB2RSTR_ADCRST +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup BUS_LL_Exported_Functions BUS Exported Functions + * @{ + */ + +/** @defgroup BUS_LL_EF_AHB1 AHB1 + * @{ + */ + +/** + * @brief Enable AHB1 peripherals clock. + * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOBEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOCEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIODEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOEEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOFEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOGEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOHEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOIEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOJEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR GPIOKEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR CRCEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR DMA1EN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR DMA2EN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR RNGEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR DMA2DEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR ETHMACEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR OTGHSEN LL_AHB1_GRP1_EnableClock\n + * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_EnableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_EnableClock(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB1ENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB1ENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Check if AHB1 peripheral clock is enabled or not + * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOBEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOCEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIODEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOEEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOFEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOGEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOHEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOIEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOJEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR GPIOKEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR CRCEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR DMA1EN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR DMA2EN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR RNGEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR DMA2DEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR ETHMACEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR OTGHSEN LL_AHB1_GRP1_IsEnabledClock\n + * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_IsEnabledClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) + * + * (*) value not defined in all devices. + * @retval State of Periphs (1 or 0). +*/ +__STATIC_INLINE uint32_t LL_AHB1_GRP1_IsEnabledClock(uint32_t Periphs) +{ + return (READ_BIT(RCC->AHB1ENR, Periphs) == Periphs); +} + +/** + * @brief Disable AHB1 peripherals clock. + * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOBEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOCEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIODEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOEEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOFEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOGEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOHEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOIEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOJEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR GPIOKEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR CRCEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR DMA1EN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR DMA2EN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR RNGEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR DMA2DEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR ETHMACEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR OTGHSEN LL_AHB1_GRP1_DisableClock\n + * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_DisableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_DisableClock(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB1ENR, Periphs); +} + +/** + * @brief Force AHB1 peripherals reset. + * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIODRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOERST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR CRCRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR DMA1RST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR DMA2RST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR RNGRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ForceReset\n + * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ForceReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_ALL + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_ForceReset(uint32_t Periphs) +{ + SET_BIT(RCC->AHB1RSTR, Periphs); +} + +/** + * @brief Release AHB1 peripherals reset. + * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIODRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOERST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR CRCRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR DMA1RST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR DMA2RST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR RNGRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ReleaseReset\n + * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ReleaseReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_ALL + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_ReleaseReset(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB1RSTR, Periphs); +} + +/** + * @brief Enable AHB1 peripheral clocks in low-power mode + * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR CRCLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR RNGLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_EnableClockLowPower\n + * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_EnableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_EnableClockLowPower(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB1LPENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB1LPENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Disable AHB1 peripheral clocks in low-power mode + * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR CRCLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR RNGLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_DisableClockLowPower\n + * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_DisableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_CRC + * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 + * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) + * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB1_GRP1_DisableClockLowPower(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB1LPENR, Periphs); +} + +/** + * @} + */ + +#if defined(RCC_AHB2_SUPPORT) +/** @defgroup BUS_LL_EF_AHB2 AHB2 + * @{ + */ + +/** + * @brief Enable AHB2 peripherals clock. + * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_EnableClock\n + * AHB2ENR CRYPEN LL_AHB2_GRP1_EnableClock\n + * AHB2ENR AESEN LL_AHB2_GRP1_EnableClock\n + * AHB2ENR HASHEN LL_AHB2_GRP1_EnableClock\n + * AHB2ENR RNGEN LL_AHB2_GRP1_EnableClock\n + * AHB2ENR OTGFSEN LL_AHB2_GRP1_EnableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_EnableClock(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB2ENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB2ENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Check if AHB2 peripheral clock is enabled or not + * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_IsEnabledClock\n + * AHB2ENR CRYPEN LL_AHB2_GRP1_IsEnabledClock\n + * AHB2ENR AESEN LL_AHB2_GRP1_IsEnabledClock\n + * AHB2ENR HASHEN LL_AHB2_GRP1_IsEnabledClock\n + * AHB2ENR RNGEN LL_AHB2_GRP1_IsEnabledClock\n + * AHB2ENR OTGFSEN LL_AHB2_GRP1_IsEnabledClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval State of Periphs (1 or 0). +*/ +__STATIC_INLINE uint32_t LL_AHB2_GRP1_IsEnabledClock(uint32_t Periphs) +{ + return (READ_BIT(RCC->AHB2ENR, Periphs) == Periphs); +} + +/** + * @brief Disable AHB2 peripherals clock. + * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_DisableClock\n + * AHB2ENR CRYPEN LL_AHB2_GRP1_DisableClock\n + * AHB2ENR AESEN LL_AHB2_GRP1_DisableClock\n + * AHB2ENR HASHEN LL_AHB2_GRP1_DisableClock\n + * AHB2ENR RNGEN LL_AHB2_GRP1_DisableClock\n + * AHB2ENR OTGFSEN LL_AHB2_GRP1_DisableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_DisableClock(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB2ENR, Periphs); +} + +/** + * @brief Force AHB2 peripherals reset. + * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ForceReset\n + * AHB2RSTR CRYPRST LL_AHB2_GRP1_ForceReset\n + * AHB2RSTR AESRST LL_AHB2_GRP1_ForceReset\n + * AHB2RSTR HASHRST LL_AHB2_GRP1_ForceReset\n + * AHB2RSTR RNGRST LL_AHB2_GRP1_ForceReset\n + * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ForceReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_ALL + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_ForceReset(uint32_t Periphs) +{ + SET_BIT(RCC->AHB2RSTR, Periphs); +} + +/** + * @brief Release AHB2 peripherals reset. + * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ReleaseReset\n + * AHB2RSTR CRYPRST LL_AHB2_GRP1_ReleaseReset\n + * AHB2RSTR AESRST LL_AHB2_GRP1_ReleaseReset\n + * AHB2RSTR HASHRST LL_AHB2_GRP1_ReleaseReset\n + * AHB2RSTR RNGRST LL_AHB2_GRP1_ReleaseReset\n + * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ReleaseReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_ALL + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_ReleaseReset(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB2RSTR, Periphs); +} + +/** + * @brief Enable AHB2 peripheral clocks in low-power mode + * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_EnableClockLowPower\n + * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_EnableClockLowPower\n + * AHB2LPENR AESLPEN LL_AHB2_GRP1_EnableClockLowPower\n + * AHB2LPENR HASHLPEN LL_AHB2_GRP1_EnableClockLowPower\n + * AHB2LPENR RNGLPEN LL_AHB2_GRP1_EnableClockLowPower\n + * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_EnableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_EnableClockLowPower(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB2LPENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB2LPENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Disable AHB2 peripheral clocks in low-power mode + * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_DisableClockLowPower\n + * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_DisableClockLowPower\n + * AHB2LPENR AESLPEN LL_AHB2_GRP1_DisableClockLowPower\n + * AHB2LPENR HASHLPEN LL_AHB2_GRP1_DisableClockLowPower\n + * AHB2LPENR RNGLPEN LL_AHB2_GRP1_DisableClockLowPower\n + * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_DisableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) + * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB2_GRP1_DisableClockLowPower(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB2LPENR, Periphs); +} + +/** + * @} + */ +#endif /* RCC_AHB2_SUPPORT */ + +#if defined(RCC_AHB3_SUPPORT) +/** @defgroup BUS_LL_EF_AHB3 AHB3 + * @{ + */ + +/** + * @brief Enable AHB3 peripherals clock. + * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_EnableClock\n + * AHB3ENR FSMCEN LL_AHB3_GRP1_EnableClock\n + * AHB3ENR QSPIEN LL_AHB3_GRP1_EnableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_EnableClock(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB3ENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB3ENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Check if AHB3 peripheral clock is enabled or not + * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_IsEnabledClock\n + * AHB3ENR FSMCEN LL_AHB3_GRP1_IsEnabledClock\n + * AHB3ENR QSPIEN LL_AHB3_GRP1_IsEnabledClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval State of Periphs (1 or 0). +*/ +__STATIC_INLINE uint32_t LL_AHB3_GRP1_IsEnabledClock(uint32_t Periphs) +{ + return (READ_BIT(RCC->AHB3ENR, Periphs) == Periphs); +} + +/** + * @brief Disable AHB3 peripherals clock. + * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_DisableClock\n + * AHB3ENR FSMCEN LL_AHB3_GRP1_DisableClock\n + * AHB3ENR QSPIEN LL_AHB3_GRP1_DisableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_DisableClock(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB3ENR, Periphs); +} + +/** + * @brief Force AHB3 peripherals reset. + * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ForceReset\n + * AHB3RSTR FSMCRST LL_AHB3_GRP1_ForceReset\n + * AHB3RSTR QSPIRST LL_AHB3_GRP1_ForceReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_ALL + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_ForceReset(uint32_t Periphs) +{ + SET_BIT(RCC->AHB3RSTR, Periphs); +} + +/** + * @brief Release AHB3 peripherals reset. + * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ReleaseReset\n + * AHB3RSTR FSMCRST LL_AHB3_GRP1_ReleaseReset\n + * AHB3RSTR QSPIRST LL_AHB3_GRP1_ReleaseReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB2_GRP1_PERIPH_ALL + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_ReleaseReset(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB3RSTR, Periphs); +} + +/** + * @brief Enable AHB3 peripheral clocks in low-power mode + * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n + * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n + * AHB3LPENR QSPILPEN LL_AHB3_GRP1_EnableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_EnableClockLowPower(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->AHB3LPENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHB3LPENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Disable AHB3 peripheral clocks in low-power mode + * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n + * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n + * AHB3LPENR QSPILPEN LL_AHB3_GRP1_DisableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) + * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_AHB3_GRP1_DisableClockLowPower(uint32_t Periphs) +{ + CLEAR_BIT(RCC->AHB3LPENR, Periphs); +} + +/** + * @} + */ +#endif /* RCC_AHB3_SUPPORT */ + +/** @defgroup BUS_LL_EF_APB1 APB1 + * @{ + */ + +/** + * @brief Enable APB1 peripherals clock. + * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM3EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM4EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM5EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM6EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM7EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM12EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM13EN LL_APB1_GRP1_EnableClock\n + * APB1ENR TIM14EN LL_APB1_GRP1_EnableClock\n + * APB1ENR LPTIM1EN LL_APB1_GRP1_EnableClock\n + * APB1ENR WWDGEN LL_APB1_GRP1_EnableClock\n + * APB1ENR SPI2EN LL_APB1_GRP1_EnableClock\n + * APB1ENR SPI3EN LL_APB1_GRP1_EnableClock\n + * APB1ENR SPDIFRXEN LL_APB1_GRP1_EnableClock\n + * APB1ENR USART2EN LL_APB1_GRP1_EnableClock\n + * APB1ENR USART3EN LL_APB1_GRP1_EnableClock\n + * APB1ENR UART4EN LL_APB1_GRP1_EnableClock\n + * APB1ENR UART5EN LL_APB1_GRP1_EnableClock\n + * APB1ENR I2C1EN LL_APB1_GRP1_EnableClock\n + * APB1ENR I2C2EN LL_APB1_GRP1_EnableClock\n + * APB1ENR I2C3EN LL_APB1_GRP1_EnableClock\n + * APB1ENR FMPI2C1EN LL_APB1_GRP1_EnableClock\n + * APB1ENR CAN1EN LL_APB1_GRP1_EnableClock\n + * APB1ENR CAN2EN LL_APB1_GRP1_EnableClock\n + * APB1ENR CAN3EN LL_APB1_GRP1_EnableClock\n + * APB1ENR CECEN LL_APB1_GRP1_EnableClock\n + * APB1ENR PWREN LL_APB1_GRP1_EnableClock\n + * APB1ENR DACEN LL_APB1_GRP1_EnableClock\n + * APB1ENR UART7EN LL_APB1_GRP1_EnableClock\n + * APB1ENR UART8EN LL_APB1_GRP1_EnableClock\n + * APB1ENR RTCAPBEN LL_APB1_GRP1_EnableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_EnableClock(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->APB1ENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->APB1ENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Check if APB1 peripheral clock is enabled or not + * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM3EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM4EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM5EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM6EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM7EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM12EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM13EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR TIM14EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR LPTIM1EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR WWDGEN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR SPI2EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR SPI3EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR SPDIFRXEN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR USART2EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR USART3EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR UART4EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR UART5EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR I2C1EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR I2C2EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR I2C3EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR FMPI2C1EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR CAN1EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR CAN2EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR CAN3EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR CECEN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR PWREN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR DACEN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR UART7EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR UART8EN LL_APB1_GRP1_IsEnabledClock\n + * APB1ENR RTCAPBEN LL_APB1_GRP1_IsEnabledClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) + * + * (*) value not defined in all devices. + * @retval State of Periphs (1 or 0). +*/ +__STATIC_INLINE uint32_t LL_APB1_GRP1_IsEnabledClock(uint32_t Periphs) +{ + return (READ_BIT(RCC->APB1ENR, Periphs) == Periphs); +} + +/** + * @brief Disable APB1 peripherals clock. + * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM3EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM4EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM5EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM6EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM7EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM12EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM13EN LL_APB1_GRP1_DisableClock\n + * APB1ENR TIM14EN LL_APB1_GRP1_DisableClock\n + * APB1ENR LPTIM1EN LL_APB1_GRP1_DisableClock\n + * APB1ENR WWDGEN LL_APB1_GRP1_DisableClock\n + * APB1ENR SPI2EN LL_APB1_GRP1_DisableClock\n + * APB1ENR SPI3EN LL_APB1_GRP1_DisableClock\n + * APB1ENR SPDIFRXEN LL_APB1_GRP1_DisableClock\n + * APB1ENR USART2EN LL_APB1_GRP1_DisableClock\n + * APB1ENR USART3EN LL_APB1_GRP1_DisableClock\n + * APB1ENR UART4EN LL_APB1_GRP1_DisableClock\n + * APB1ENR UART5EN LL_APB1_GRP1_DisableClock\n + * APB1ENR I2C1EN LL_APB1_GRP1_DisableClock\n + * APB1ENR I2C2EN LL_APB1_GRP1_DisableClock\n + * APB1ENR I2C3EN LL_APB1_GRP1_DisableClock\n + * APB1ENR FMPI2C1EN LL_APB1_GRP1_DisableClock\n + * APB1ENR CAN1EN LL_APB1_GRP1_DisableClock\n + * APB1ENR CAN2EN LL_APB1_GRP1_DisableClock\n + * APB1ENR CAN3EN LL_APB1_GRP1_DisableClock\n + * APB1ENR CECEN LL_APB1_GRP1_DisableClock\n + * APB1ENR PWREN LL_APB1_GRP1_DisableClock\n + * APB1ENR DACEN LL_APB1_GRP1_DisableClock\n + * APB1ENR UART7EN LL_APB1_GRP1_DisableClock\n + * APB1ENR UART8EN LL_APB1_GRP1_DisableClock\n + * APB1ENR RTCAPBEN LL_APB1_GRP1_DisableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_DisableClock(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB1ENR, Periphs); +} + +/** + * @brief Force APB1 peripherals reset. + * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM3RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM4RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM5RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM6RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM7RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM12RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM13RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR TIM14RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR LPTIM1RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR WWDGRST LL_APB1_GRP1_ForceReset\n + * APB1RSTR SPI2RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR SPI3RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ForceReset\n + * APB1RSTR USART2RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR USART3RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR UART4RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR UART5RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR I2C1RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR I2C2RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR I2C3RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR CAN1RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR CAN2RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR CAN3RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR CECRST LL_APB1_GRP1_ForceReset\n + * APB1RSTR PWRRST LL_APB1_GRP1_ForceReset\n + * APB1RSTR DACRST LL_APB1_GRP1_ForceReset\n + * APB1RSTR UART7RST LL_APB1_GRP1_ForceReset\n + * APB1RSTR UART8RST LL_APB1_GRP1_ForceReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_ForceReset(uint32_t Periphs) +{ + SET_BIT(RCC->APB1RSTR, Periphs); +} + +/** + * @brief Release APB1 peripherals reset. + * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM3RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM4RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM5RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM6RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM7RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM12RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM13RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR TIM14RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR LPTIM1RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR WWDGRST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR SPI2RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR SPI3RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR USART2RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR USART3RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR UART4RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR UART5RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR I2C1RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR I2C2RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR I2C3RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR CAN1RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR CAN2RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR CAN3RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR CECRST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR PWRRST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR DACRST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR UART7RST LL_APB1_GRP1_ReleaseReset\n + * APB1RSTR UART8RST LL_APB1_GRP1_ReleaseReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_ReleaseReset(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB1RSTR, Periphs); +} + +/** + * @brief Enable APB1 peripheral clocks in low-power mode + * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM3LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM4LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM5LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM6LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM7LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM12LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM13LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR TIM14LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR WWDGLPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR SPI2LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR SPI3LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR USART2LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR USART3LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR UART4LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR UART5LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR I2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR I2C2LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR I2C3LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR CAN1LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR CAN2LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR CAN3LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR CECLPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR PWRLPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR DACLPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR UART7LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR UART8LPEN LL_APB1_GRP1_EnableClockLowPower\n + * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_EnableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_EnableClockLowPower(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->APB1LPENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->APB1LPENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Disable APB1 peripheral clocks in low-power mode + * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM3LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM4LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM5LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM6LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM7LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM12LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM13LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR TIM14LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR WWDGLPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR SPI2LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR SPI3LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR USART2LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR USART3LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR UART4LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR UART5LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR I2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR I2C2LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR I2C3LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR CAN1LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR CAN2LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR CAN3LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR CECLPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR PWRLPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR DACLPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR UART7LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR UART8LPEN LL_APB1_GRP1_DisableClockLowPower\n + * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_DisableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 + * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_WWDG + * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) + * @arg @ref LL_APB1_GRP1_PERIPH_USART2 + * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 + * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) + * @arg @ref LL_APB1_GRP1_PERIPH_PWR + * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) + * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB1_GRP1_DisableClockLowPower(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB1LPENR, Periphs); +} + +/** + * @} + */ + +/** @defgroup BUS_LL_EF_APB2 APB2 + * @{ + */ + +/** + * @brief Enable APB2 peripherals clock. + * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR TIM8EN LL_APB2_GRP1_EnableClock\n + * APB2ENR USART1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR USART6EN LL_APB2_GRP1_EnableClock\n + * APB2ENR UART9EN LL_APB2_GRP1_EnableClock\n + * APB2ENR UART10EN LL_APB2_GRP1_EnableClock\n + * APB2ENR ADC1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR ADC2EN LL_APB2_GRP1_EnableClock\n + * APB2ENR ADC3EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SDIOEN LL_APB2_GRP1_EnableClock\n + * APB2ENR SPI1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SPI4EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SYSCFGEN LL_APB2_GRP1_EnableClock\n + * APB2ENR EXTITEN LL_APB2_GRP1_EnableClock\n + * APB2ENR TIM9EN LL_APB2_GRP1_EnableClock\n + * APB2ENR TIM10EN LL_APB2_GRP1_EnableClock\n + * APB2ENR TIM11EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SPI5EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SPI6EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SAI1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR SAI2EN LL_APB2_GRP1_EnableClock\n + * APB2ENR LTDCEN LL_APB2_GRP1_EnableClock\n + * APB2ENR DSIEN LL_APB2_GRP1_EnableClock\n + * APB2ENR DFSDM1EN LL_APB2_GRP1_EnableClock\n + * APB2ENR DFSDM2EN LL_APB2_GRP1_EnableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 + * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_EnableClock(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->APB2ENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->APB2ENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Check if APB2 peripheral clock is enabled or not + * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR TIM8EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR USART1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR USART6EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR UART9EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR UART10EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR ADC1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR ADC2EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR ADC3EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SDIOEN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SPI1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SPI4EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SYSCFGEN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR EXTITEN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR TIM9EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR TIM10EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR TIM11EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SPI5EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SPI6EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SAI1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR SAI2EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR LTDCEN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR DSIEN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR DFSDM1EN LL_APB2_GRP1_IsEnabledClock\n + * APB2ENR DFSDM2EN LL_APB2_GRP1_IsEnabledClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 + * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval State of Periphs (1 or 0). +*/ +__STATIC_INLINE uint32_t LL_APB2_GRP1_IsEnabledClock(uint32_t Periphs) +{ + return (READ_BIT(RCC->APB2ENR, Periphs) == Periphs); +} + +/** + * @brief Disable APB2 peripherals clock. + * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR TIM8EN LL_APB2_GRP1_DisableClock\n + * APB2ENR USART1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR USART6EN LL_APB2_GRP1_DisableClock\n + * APB2ENR UART9EN LL_APB2_GRP1_DisableClock\n + * APB2ENR UART10EN LL_APB2_GRP1_DisableClock\n + * APB2ENR ADC1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR ADC2EN LL_APB2_GRP1_DisableClock\n + * APB2ENR ADC3EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SDIOEN LL_APB2_GRP1_DisableClock\n + * APB2ENR SPI1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SPI4EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SYSCFGEN LL_APB2_GRP1_DisableClock\n + * APB2ENR EXTITEN LL_APB2_GRP1_DisableClock\n + * APB2ENR TIM9EN LL_APB2_GRP1_DisableClock\n + * APB2ENR TIM10EN LL_APB2_GRP1_DisableClock\n + * APB2ENR TIM11EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SPI5EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SPI6EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SAI1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR SAI2EN LL_APB2_GRP1_DisableClock\n + * APB2ENR LTDCEN LL_APB2_GRP1_DisableClock\n + * APB2ENR DSIEN LL_APB2_GRP1_DisableClock\n + * APB2ENR DFSDM1EN LL_APB2_GRP1_DisableClock\n + * APB2ENR DFSDM2EN LL_APB2_GRP1_DisableClock + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 + * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_DisableClock(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB2ENR, Periphs); +} + +/** + * @brief Force APB2 peripherals reset. + * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR TIM8RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR USART1RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR USART6RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR UART9RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR UART10RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR ADCRST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SDIORST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SPI1RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SPI4RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SYSCFGRST LL_APB2_GRP1_ForceReset\n + * APB2RSTR TIM9RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR TIM10RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR TIM11RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SPI5RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SPI6RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SAI1RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR SAI2RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR LTDCRST LL_APB2_GRP1_ForceReset\n + * APB2RSTR DSIRST LL_APB2_GRP1_ForceReset\n + * APB2RSTR DFSDM1RST LL_APB2_GRP1_ForceReset\n + * APB2RSTR DFSDM2RST LL_APB2_GRP1_ForceReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_ALL + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_ForceReset(uint32_t Periphs) +{ + SET_BIT(RCC->APB2RSTR, Periphs); +} + +/** + * @brief Release APB2 peripherals reset. + * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR TIM8RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR USART1RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR USART6RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR UART9RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR UART10RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR ADCRST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SDIORST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SPI1RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SPI4RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SYSCFGRST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR TIM9RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR TIM10RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR TIM11RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SPI5RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SPI6RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SAI1RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR SAI2RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR LTDCRST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR DSIRST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR DFSDM1RST LL_APB2_GRP1_ReleaseReset\n + * APB2RSTR DFSDM2RST LL_APB2_GRP1_ReleaseReset + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_ALL + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_ReleaseReset(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB2RSTR, Periphs); +} + +/** + * @brief Enable APB2 peripheral clocks in low-power mode + * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR TIM8LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR USART1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR USART6LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR UART9LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR UART10LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR ADC1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR ADC2LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR ADC3LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SDIOLPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SPI1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SPI4LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR EXTITLPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR TIM9LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR TIM10LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR TIM11LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SPI5LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SPI6LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SAI1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR SAI2LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR LTDCLPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n + * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_EnableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 + * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_EnableClockLowPower(uint32_t Periphs) +{ + __IO uint32_t tmpreg; + SET_BIT(RCC->APB2LPENR, Periphs); + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->APB2LPENR, Periphs); + (void)tmpreg; +} + +/** + * @brief Disable APB2 peripheral clocks in low-power mode + * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR TIM8LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR USART1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR USART6LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR UART9LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR UART10LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR ADC1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR ADC2LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR ADC3LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SDIOLPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SPI1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SPI4LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR EXTITLPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR TIM9LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR TIM10LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR TIM11LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SPI5LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SPI6LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SAI1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR SAI2LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR LTDCLPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n + * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_DisableClockLowPower + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_USART1 + * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 + * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG + * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 + * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 + * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) + * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) + * + * (*) value not defined in all devices. + * @retval None +*/ +__STATIC_INLINE void LL_APB2_GRP1_DisableClockLowPower(uint32_t Periphs) +{ + CLEAR_BIT(RCC->APB2LPENR, Periphs); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(RCC) */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_BUS_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h index d478e13..4b11b73 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h @@ -1,637 +1,637 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL CORTEX driver contains a set of generic APIs that can be - used by user: - (+) SYSTICK configuration used by LL_mDelay and LL_Init1msTick - functions - (+) Low power mode configuration (SCB register of Cortex-MCU) - (+) MPU API to configure and enable regions - (MPU services provided only on some devices) - (+) API to access to MCU info (CPUID register) - (+) API to enable fault handler (SHCSR accesses) - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_CORTEX_H -#define __STM32F4xx_LL_CORTEX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup CORTEX_LL CORTEX - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_LL_EC_CLKSOURCE_HCLK SYSTICK Clock Source - * @{ - */ -#define LL_SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U /*!< AHB clock divided by 8 selected as SysTick clock source.*/ -#define LL_SYSTICK_CLKSOURCE_HCLK SysTick_CTRL_CLKSOURCE_Msk /*!< AHB clock selected as SysTick clock source. */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_FAULT Handler Fault type - * @{ - */ -#define LL_HANDLER_FAULT_USG SCB_SHCSR_USGFAULTENA_Msk /*!< Usage fault */ -#define LL_HANDLER_FAULT_BUS SCB_SHCSR_BUSFAULTENA_Msk /*!< Bus fault */ -#define LL_HANDLER_FAULT_MEM SCB_SHCSR_MEMFAULTENA_Msk /*!< Memory management fault */ -/** - * @} - */ - -#if __MPU_PRESENT - -/** @defgroup CORTEX_LL_EC_CTRL_HFNMI_PRIVDEF MPU Control - * @{ - */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF_NONE 0x00000000U /*!< Disable NMI and privileged SW access */ -#define LL_MPU_CTRL_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk /*!< Enables the operation of MPU during hard fault, NMI, and FAULTMASK handlers */ -#define LL_MPU_CTRL_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk /*!< Enable privileged software access to default memory map */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) /*!< Enable NMI and privileged SW access */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION MPU Region Number - * @{ - */ -#define LL_MPU_REGION_NUMBER0 0x00U /*!< REGION Number 0 */ -#define LL_MPU_REGION_NUMBER1 0x01U /*!< REGION Number 1 */ -#define LL_MPU_REGION_NUMBER2 0x02U /*!< REGION Number 2 */ -#define LL_MPU_REGION_NUMBER3 0x03U /*!< REGION Number 3 */ -#define LL_MPU_REGION_NUMBER4 0x04U /*!< REGION Number 4 */ -#define LL_MPU_REGION_NUMBER5 0x05U /*!< REGION Number 5 */ -#define LL_MPU_REGION_NUMBER6 0x06U /*!< REGION Number 6 */ -#define LL_MPU_REGION_NUMBER7 0x07U /*!< REGION Number 7 */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_SIZE MPU Region Size - * @{ - */ -#define LL_MPU_REGION_SIZE_32B (0x04U << MPU_RASR_SIZE_Pos) /*!< 32B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64B (0x05U << MPU_RASR_SIZE_Pos) /*!< 64B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128B (0x06U << MPU_RASR_SIZE_Pos) /*!< 128B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256B (0x07U << MPU_RASR_SIZE_Pos) /*!< 256B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512B (0x08U << MPU_RASR_SIZE_Pos) /*!< 512B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1KB (0x09U << MPU_RASR_SIZE_Pos) /*!< 1KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2KB (0x0AU << MPU_RASR_SIZE_Pos) /*!< 2KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4KB (0x0BU << MPU_RASR_SIZE_Pos) /*!< 4KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8KB (0x0CU << MPU_RASR_SIZE_Pos) /*!< 8KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16KB (0x0DU << MPU_RASR_SIZE_Pos) /*!< 16KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32KB (0x0EU << MPU_RASR_SIZE_Pos) /*!< 32KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64KB (0x0FU << MPU_RASR_SIZE_Pos) /*!< 64KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128KB (0x10U << MPU_RASR_SIZE_Pos) /*!< 128KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256KB (0x11U << MPU_RASR_SIZE_Pos) /*!< 256KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512KB (0x12U << MPU_RASR_SIZE_Pos) /*!< 512KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1MB (0x13U << MPU_RASR_SIZE_Pos) /*!< 1MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2MB (0x14U << MPU_RASR_SIZE_Pos) /*!< 2MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4MB (0x15U << MPU_RASR_SIZE_Pos) /*!< 4MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8MB (0x16U << MPU_RASR_SIZE_Pos) /*!< 8MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16MB (0x17U << MPU_RASR_SIZE_Pos) /*!< 16MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32MB (0x18U << MPU_RASR_SIZE_Pos) /*!< 32MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64MB (0x19U << MPU_RASR_SIZE_Pos) /*!< 64MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128MB (0x1AU << MPU_RASR_SIZE_Pos) /*!< 128MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256MB (0x1BU << MPU_RASR_SIZE_Pos) /*!< 256MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512MB (0x1CU << MPU_RASR_SIZE_Pos) /*!< 512MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1GB (0x1DU << MPU_RASR_SIZE_Pos) /*!< 1GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2GB (0x1EU << MPU_RASR_SIZE_Pos) /*!< 2GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4GB (0x1FU << MPU_RASR_SIZE_Pos) /*!< 4GB Size of the MPU protection region */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_PRIVILEDGES MPU Region Privileges - * @{ - */ -#define LL_MPU_REGION_NO_ACCESS (0x00U << MPU_RASR_AP_Pos) /*!< No access*/ -#define LL_MPU_REGION_PRIV_RW (0x01U << MPU_RASR_AP_Pos) /*!< RW privileged (privileged access only)*/ -#define LL_MPU_REGION_PRIV_RW_URO (0x02U << MPU_RASR_AP_Pos) /*!< RW privileged - RO user (Write in a user program generates a fault) */ -#define LL_MPU_REGION_FULL_ACCESS (0x03U << MPU_RASR_AP_Pos) /*!< RW privileged & user (Full access) */ -#define LL_MPU_REGION_PRIV_RO (0x05U << MPU_RASR_AP_Pos) /*!< RO privileged (privileged read only)*/ -#define LL_MPU_REGION_PRIV_RO_URO (0x06U << MPU_RASR_AP_Pos) /*!< RO privileged & user (read only) */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_TEX MPU TEX Level - * @{ - */ -#define LL_MPU_TEX_LEVEL0 (0x00U << MPU_RASR_TEX_Pos) /*!< b000 for TEX bits */ -#define LL_MPU_TEX_LEVEL1 (0x01U << MPU_RASR_TEX_Pos) /*!< b001 for TEX bits */ -#define LL_MPU_TEX_LEVEL2 (0x02U << MPU_RASR_TEX_Pos) /*!< b010 for TEX bits */ -#define LL_MPU_TEX_LEVEL4 (0x04U << MPU_RASR_TEX_Pos) /*!< b100 for TEX bits */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_INSTRUCTION_ACCESS MPU Instruction Access - * @{ - */ -#define LL_MPU_INSTRUCTION_ACCESS_ENABLE 0x00U /*!< Instruction fetches enabled */ -#define LL_MPU_INSTRUCTION_ACCESS_DISABLE MPU_RASR_XN_Msk /*!< Instruction fetches disabled*/ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_SHAREABLE_ACCESS MPU Shareable Access - * @{ - */ -#define LL_MPU_ACCESS_SHAREABLE MPU_RASR_S_Msk /*!< Shareable memory attribute */ -#define LL_MPU_ACCESS_NOT_SHAREABLE 0x00U /*!< Not Shareable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_CACHEABLE_ACCESS MPU Cacheable Access - * @{ - */ -#define LL_MPU_ACCESS_CACHEABLE MPU_RASR_C_Msk /*!< Cacheable memory attribute */ -#define LL_MPU_ACCESS_NOT_CACHEABLE 0x00U /*!< Not Cacheable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_BUFFERABLE_ACCESS MPU Bufferable Access - * @{ - */ -#define LL_MPU_ACCESS_BUFFERABLE MPU_RASR_B_Msk /*!< Bufferable memory attribute */ -#define LL_MPU_ACCESS_NOT_BUFFERABLE 0x00U /*!< Not Bufferable memory attribute */ -/** - * @} - */ -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Functions CORTEX Exported Functions - * @{ - */ - -/** @defgroup CORTEX_LL_EF_SYSTICK SYSTICK - * @{ - */ - -/** - * @brief This function checks if the Systick counter flag is active or not. - * @note It can be used in timeout function on application side. - * @rmtoll STK_CTRL COUNTFLAG LL_SYSTICK_IsActiveCounterFlag - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsActiveCounterFlag(void) -{ - return ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == (SysTick_CTRL_COUNTFLAG_Msk)); -} - -/** - * @brief Configures the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_SetClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_SetClkSource(uint32_t Source) -{ - if (Source == LL_SYSTICK_CLKSOURCE_HCLK) - { - SET_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } - else - { - CLEAR_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } -} - -/** - * @brief Get the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_GetClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - */ -__STATIC_INLINE uint32_t LL_SYSTICK_GetClkSource(void) -{ - return READ_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); -} - -/** - * @brief Enable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_EnableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_EnableIT(void) -{ - SET_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Disable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_DisableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_DisableIT(void) -{ - CLEAR_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Checks if the SYSTICK interrupt is enabled or disabled. - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_IsEnabledIT - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsEnabledIT(void) -{ - return (READ_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk) == (SysTick_CTRL_TICKINT_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_LOW_POWER_MODE LOW POWER MODE - * @{ - */ - -/** - * @brief Processor uses sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleep(void) -{ - /* Clear SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Processor uses deep sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableDeepSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableDeepSleep(void) -{ - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Configures sleep-on-exit when returning from Handler mode to Thread mode. - * @note Setting this bit to 1 enables an interrupt-driven application to avoid returning to an - * empty main application. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_EnableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleepOnExit(void) -{ - /* Set SLEEPONEXIT bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Do not sleep when returning to Thread mode. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_DisableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableSleepOnExit(void) -{ - /* Clear SLEEPONEXIT bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Enabled events and all interrupts, including disabled interrupts, can wakeup the - * processor. - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_EnableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableEventOnPend(void) -{ - /* Set SEVEONPEND bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @brief Only enabled interrupts or events can wakeup the processor, disabled interrupts are - * excluded - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_DisableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableEventOnPend(void) -{ - /* Clear SEVEONPEND bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_HANDLER HANDLER - * @{ - */ - -/** - * @brief Enable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_EnableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_EnableFault(uint32_t Fault) -{ - /* Enable the system handler fault */ - SET_BIT(SCB->SHCSR, Fault); -} - -/** - * @brief Disable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_DisableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_DisableFault(uint32_t Fault) -{ - /* Disable the system handler fault */ - CLEAR_BIT(SCB->SHCSR, Fault); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_MCU_INFO MCU INFO - * @{ - */ - -/** - * @brief Get Implementer code - * @rmtoll SCB_CPUID IMPLEMENTER LL_CPUID_GetImplementer - * @retval Value should be equal to 0x41 for ARM - */ -__STATIC_INLINE uint32_t LL_CPUID_GetImplementer(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_IMPLEMENTER_Msk) >> SCB_CPUID_IMPLEMENTER_Pos); -} - -/** - * @brief Get Variant number (The r value in the rnpn product revision identifier) - * @rmtoll SCB_CPUID VARIANT LL_CPUID_GetVariant - * @retval Value between 0 and 255 (0x0: revision 0) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetVariant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_VARIANT_Msk) >> SCB_CPUID_VARIANT_Pos); -} - -/** - * @brief Get Constant number - * @rmtoll SCB_CPUID ARCHITECTURE LL_CPUID_GetConstant - * @retval Value should be equal to 0xF for Cortex-M4 devices - */ -__STATIC_INLINE uint32_t LL_CPUID_GetConstant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_ARCHITECTURE_Msk) >> SCB_CPUID_ARCHITECTURE_Pos); -} - -/** - * @brief Get Part number - * @rmtoll SCB_CPUID PARTNO LL_CPUID_GetParNo - * @retval Value should be equal to 0xC24 for Cortex-M4 - */ -__STATIC_INLINE uint32_t LL_CPUID_GetParNo(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_PARTNO_Msk) >> SCB_CPUID_PARTNO_Pos); -} - -/** - * @brief Get Revision number (The p value in the rnpn product revision identifier, indicates patch release) - * @rmtoll SCB_CPUID REVISION LL_CPUID_GetRevision - * @retval Value between 0 and 255 (0x1: patch 1) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetRevision(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_REVISION_Msk) >> SCB_CPUID_REVISION_Pos); -} - -/** - * @} - */ - -#if __MPU_PRESENT -/** @defgroup CORTEX_LL_EF_MPU MPU - * @{ - */ - -/** - * @brief Enable MPU with input options - * @rmtoll MPU_CTRL ENABLE LL_MPU_Enable - * @param Options This parameter can be one of the following values: - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF_NONE - * @arg @ref LL_MPU_CTRL_HARDFAULT_NMI - * @arg @ref LL_MPU_CTRL_PRIVILEGED_DEFAULT - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF - * @retval None - */ -__STATIC_INLINE void LL_MPU_Enable(uint32_t Options) -{ - /* Enable the MPU*/ - WRITE_REG(MPU->CTRL, (MPU_CTRL_ENABLE_Msk | Options)); - /* Ensure MPU settings take effects */ - __DSB(); - /* Sequence instruction fetches using update settings */ - __ISB(); -} - -/** - * @brief Disable MPU - * @rmtoll MPU_CTRL ENABLE LL_MPU_Disable - * @retval None - */ -__STATIC_INLINE void LL_MPU_Disable(void) -{ - /* Make sure outstanding transfers are done */ - __DMB(); - /* Disable MPU*/ - WRITE_REG(MPU->CTRL, 0U); -} - -/** - * @brief Check if MPU is enabled or not - * @rmtoll MPU_CTRL ENABLE LL_MPU_IsEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_MPU_IsEnabled(void) -{ - return (READ_BIT(MPU->CTRL, MPU_CTRL_ENABLE_Msk) == (MPU_CTRL_ENABLE_Msk)); -} - -/** - * @brief Enable a MPU region - * @rmtoll MPU_RASR ENABLE LL_MPU_EnableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_EnableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Enable the MPU region */ - SET_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @brief Configure and enable a region - * @rmtoll MPU_RNR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR ADDR LL_MPU_ConfigRegion\n - * MPU_RASR XN LL_MPU_ConfigRegion\n - * MPU_RASR AP LL_MPU_ConfigRegion\n - * MPU_RASR S LL_MPU_ConfigRegion\n - * MPU_RASR C LL_MPU_ConfigRegion\n - * MPU_RASR B LL_MPU_ConfigRegion\n - * MPU_RASR SIZE LL_MPU_ConfigRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @param Address Value of region base address - * @param SubRegionDisable Sub-region disable value between Min_Data = 0x00 and Max_Data = 0xFF - * @param Attributes This parameter can be a combination of the following values: - * @arg @ref LL_MPU_REGION_SIZE_32B or @ref LL_MPU_REGION_SIZE_64B or @ref LL_MPU_REGION_SIZE_128B or @ref LL_MPU_REGION_SIZE_256B or @ref LL_MPU_REGION_SIZE_512B - * or @ref LL_MPU_REGION_SIZE_1KB or @ref LL_MPU_REGION_SIZE_2KB or @ref LL_MPU_REGION_SIZE_4KB or @ref LL_MPU_REGION_SIZE_8KB or @ref LL_MPU_REGION_SIZE_16KB - * or @ref LL_MPU_REGION_SIZE_32KB or @ref LL_MPU_REGION_SIZE_64KB or @ref LL_MPU_REGION_SIZE_128KB or @ref LL_MPU_REGION_SIZE_256KB or @ref LL_MPU_REGION_SIZE_512KB - * or @ref LL_MPU_REGION_SIZE_1MB or @ref LL_MPU_REGION_SIZE_2MB or @ref LL_MPU_REGION_SIZE_4MB or @ref LL_MPU_REGION_SIZE_8MB or @ref LL_MPU_REGION_SIZE_16MB - * or @ref LL_MPU_REGION_SIZE_32MB or @ref LL_MPU_REGION_SIZE_64MB or @ref LL_MPU_REGION_SIZE_128MB or @ref LL_MPU_REGION_SIZE_256MB or @ref LL_MPU_REGION_SIZE_512MB - * or @ref LL_MPU_REGION_SIZE_1GB or @ref LL_MPU_REGION_SIZE_2GB or @ref LL_MPU_REGION_SIZE_4GB - * @arg @ref LL_MPU_REGION_NO_ACCESS or @ref LL_MPU_REGION_PRIV_RW or @ref LL_MPU_REGION_PRIV_RW_URO or @ref LL_MPU_REGION_FULL_ACCESS - * or @ref LL_MPU_REGION_PRIV_RO or @ref LL_MPU_REGION_PRIV_RO_URO - * @arg @ref LL_MPU_TEX_LEVEL0 or @ref LL_MPU_TEX_LEVEL1 or @ref LL_MPU_TEX_LEVEL2 or @ref LL_MPU_TEX_LEVEL4 - * @arg @ref LL_MPU_INSTRUCTION_ACCESS_ENABLE or @ref LL_MPU_INSTRUCTION_ACCESS_DISABLE - * @arg @ref LL_MPU_ACCESS_SHAREABLE or @ref LL_MPU_ACCESS_NOT_SHAREABLE - * @arg @ref LL_MPU_ACCESS_CACHEABLE or @ref LL_MPU_ACCESS_NOT_CACHEABLE - * @arg @ref LL_MPU_ACCESS_BUFFERABLE or @ref LL_MPU_ACCESS_NOT_BUFFERABLE - * @retval None - */ -__STATIC_INLINE void LL_MPU_ConfigRegion(uint32_t Region, uint32_t SubRegionDisable, uint32_t Address, uint32_t Attributes) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Set base address */ - WRITE_REG(MPU->RBAR, (Address & 0xFFFFFFE0U)); - /* Configure MPU */ - WRITE_REG(MPU->RASR, (MPU_RASR_ENABLE_Msk | Attributes | SubRegionDisable << MPU_RASR_SRD_Pos)); -} - -/** - * @brief Disable a region - * @rmtoll MPU_RNR REGION LL_MPU_DisableRegion\n - * MPU_RASR ENABLE LL_MPU_DisableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_DisableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Disable the MPU region */ - CLEAR_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @} - */ - -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_CORTEX_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_cortex.h + * @author MCD Application Team + * @brief Header file of CORTEX LL module. + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The LL CORTEX driver contains a set of generic APIs that can be + used by user: + (+) SYSTICK configuration used by LL_mDelay and LL_Init1msTick + functions + (+) Low power mode configuration (SCB register of Cortex-MCU) + (+) MPU API to configure and enable regions + (MPU services provided only on some devices) + (+) API to access to MCU info (CPUID register) + (+) API to enable fault handler (SHCSR accesses) + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_CORTEX_H +#define __STM32F4xx_LL_CORTEX_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +/** @defgroup CORTEX_LL CORTEX + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ + +/* Private macros ------------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup CORTEX_LL_Exported_Constants CORTEX Exported Constants + * @{ + */ + +/** @defgroup CORTEX_LL_EC_CLKSOURCE_HCLK SYSTICK Clock Source + * @{ + */ +#define LL_SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U /*!< AHB clock divided by 8 selected as SysTick clock source.*/ +#define LL_SYSTICK_CLKSOURCE_HCLK SysTick_CTRL_CLKSOURCE_Msk /*!< AHB clock selected as SysTick clock source. */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_FAULT Handler Fault type + * @{ + */ +#define LL_HANDLER_FAULT_USG SCB_SHCSR_USGFAULTENA_Msk /*!< Usage fault */ +#define LL_HANDLER_FAULT_BUS SCB_SHCSR_BUSFAULTENA_Msk /*!< Bus fault */ +#define LL_HANDLER_FAULT_MEM SCB_SHCSR_MEMFAULTENA_Msk /*!< Memory management fault */ +/** + * @} + */ + +#if __MPU_PRESENT + +/** @defgroup CORTEX_LL_EC_CTRL_HFNMI_PRIVDEF MPU Control + * @{ + */ +#define LL_MPU_CTRL_HFNMI_PRIVDEF_NONE 0x00000000U /*!< Disable NMI and privileged SW access */ +#define LL_MPU_CTRL_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk /*!< Enables the operation of MPU during hard fault, NMI, and FAULTMASK handlers */ +#define LL_MPU_CTRL_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk /*!< Enable privileged software access to default memory map */ +#define LL_MPU_CTRL_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) /*!< Enable NMI and privileged SW access */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_REGION MPU Region Number + * @{ + */ +#define LL_MPU_REGION_NUMBER0 0x00U /*!< REGION Number 0 */ +#define LL_MPU_REGION_NUMBER1 0x01U /*!< REGION Number 1 */ +#define LL_MPU_REGION_NUMBER2 0x02U /*!< REGION Number 2 */ +#define LL_MPU_REGION_NUMBER3 0x03U /*!< REGION Number 3 */ +#define LL_MPU_REGION_NUMBER4 0x04U /*!< REGION Number 4 */ +#define LL_MPU_REGION_NUMBER5 0x05U /*!< REGION Number 5 */ +#define LL_MPU_REGION_NUMBER6 0x06U /*!< REGION Number 6 */ +#define LL_MPU_REGION_NUMBER7 0x07U /*!< REGION Number 7 */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_REGION_SIZE MPU Region Size + * @{ + */ +#define LL_MPU_REGION_SIZE_32B (0x04U << MPU_RASR_SIZE_Pos) /*!< 32B Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_64B (0x05U << MPU_RASR_SIZE_Pos) /*!< 64B Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_128B (0x06U << MPU_RASR_SIZE_Pos) /*!< 128B Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_256B (0x07U << MPU_RASR_SIZE_Pos) /*!< 256B Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_512B (0x08U << MPU_RASR_SIZE_Pos) /*!< 512B Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_1KB (0x09U << MPU_RASR_SIZE_Pos) /*!< 1KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_2KB (0x0AU << MPU_RASR_SIZE_Pos) /*!< 2KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_4KB (0x0BU << MPU_RASR_SIZE_Pos) /*!< 4KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_8KB (0x0CU << MPU_RASR_SIZE_Pos) /*!< 8KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_16KB (0x0DU << MPU_RASR_SIZE_Pos) /*!< 16KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_32KB (0x0EU << MPU_RASR_SIZE_Pos) /*!< 32KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_64KB (0x0FU << MPU_RASR_SIZE_Pos) /*!< 64KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_128KB (0x10U << MPU_RASR_SIZE_Pos) /*!< 128KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_256KB (0x11U << MPU_RASR_SIZE_Pos) /*!< 256KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_512KB (0x12U << MPU_RASR_SIZE_Pos) /*!< 512KB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_1MB (0x13U << MPU_RASR_SIZE_Pos) /*!< 1MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_2MB (0x14U << MPU_RASR_SIZE_Pos) /*!< 2MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_4MB (0x15U << MPU_RASR_SIZE_Pos) /*!< 4MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_8MB (0x16U << MPU_RASR_SIZE_Pos) /*!< 8MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_16MB (0x17U << MPU_RASR_SIZE_Pos) /*!< 16MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_32MB (0x18U << MPU_RASR_SIZE_Pos) /*!< 32MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_64MB (0x19U << MPU_RASR_SIZE_Pos) /*!< 64MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_128MB (0x1AU << MPU_RASR_SIZE_Pos) /*!< 128MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_256MB (0x1BU << MPU_RASR_SIZE_Pos) /*!< 256MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_512MB (0x1CU << MPU_RASR_SIZE_Pos) /*!< 512MB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_1GB (0x1DU << MPU_RASR_SIZE_Pos) /*!< 1GB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_2GB (0x1EU << MPU_RASR_SIZE_Pos) /*!< 2GB Size of the MPU protection region */ +#define LL_MPU_REGION_SIZE_4GB (0x1FU << MPU_RASR_SIZE_Pos) /*!< 4GB Size of the MPU protection region */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_REGION_PRIVILEDGES MPU Region Privileges + * @{ + */ +#define LL_MPU_REGION_NO_ACCESS (0x00U << MPU_RASR_AP_Pos) /*!< No access*/ +#define LL_MPU_REGION_PRIV_RW (0x01U << MPU_RASR_AP_Pos) /*!< RW privileged (privileged access only)*/ +#define LL_MPU_REGION_PRIV_RW_URO (0x02U << MPU_RASR_AP_Pos) /*!< RW privileged - RO user (Write in a user program generates a fault) */ +#define LL_MPU_REGION_FULL_ACCESS (0x03U << MPU_RASR_AP_Pos) /*!< RW privileged & user (Full access) */ +#define LL_MPU_REGION_PRIV_RO (0x05U << MPU_RASR_AP_Pos) /*!< RO privileged (privileged read only)*/ +#define LL_MPU_REGION_PRIV_RO_URO (0x06U << MPU_RASR_AP_Pos) /*!< RO privileged & user (read only) */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_TEX MPU TEX Level + * @{ + */ +#define LL_MPU_TEX_LEVEL0 (0x00U << MPU_RASR_TEX_Pos) /*!< b000 for TEX bits */ +#define LL_MPU_TEX_LEVEL1 (0x01U << MPU_RASR_TEX_Pos) /*!< b001 for TEX bits */ +#define LL_MPU_TEX_LEVEL2 (0x02U << MPU_RASR_TEX_Pos) /*!< b010 for TEX bits */ +#define LL_MPU_TEX_LEVEL4 (0x04U << MPU_RASR_TEX_Pos) /*!< b100 for TEX bits */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_INSTRUCTION_ACCESS MPU Instruction Access + * @{ + */ +#define LL_MPU_INSTRUCTION_ACCESS_ENABLE 0x00U /*!< Instruction fetches enabled */ +#define LL_MPU_INSTRUCTION_ACCESS_DISABLE MPU_RASR_XN_Msk /*!< Instruction fetches disabled*/ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_SHAREABLE_ACCESS MPU Shareable Access + * @{ + */ +#define LL_MPU_ACCESS_SHAREABLE MPU_RASR_S_Msk /*!< Shareable memory attribute */ +#define LL_MPU_ACCESS_NOT_SHAREABLE 0x00U /*!< Not Shareable memory attribute */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_CACHEABLE_ACCESS MPU Cacheable Access + * @{ + */ +#define LL_MPU_ACCESS_CACHEABLE MPU_RASR_C_Msk /*!< Cacheable memory attribute */ +#define LL_MPU_ACCESS_NOT_CACHEABLE 0x00U /*!< Not Cacheable memory attribute */ +/** + * @} + */ + +/** @defgroup CORTEX_LL_EC_BUFFERABLE_ACCESS MPU Bufferable Access + * @{ + */ +#define LL_MPU_ACCESS_BUFFERABLE MPU_RASR_B_Msk /*!< Bufferable memory attribute */ +#define LL_MPU_ACCESS_NOT_BUFFERABLE 0x00U /*!< Not Bufferable memory attribute */ +/** + * @} + */ +#endif /* __MPU_PRESENT */ +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup CORTEX_LL_Exported_Functions CORTEX Exported Functions + * @{ + */ + +/** @defgroup CORTEX_LL_EF_SYSTICK SYSTICK + * @{ + */ + +/** + * @brief This function checks if the Systick counter flag is active or not. + * @note It can be used in timeout function on application side. + * @rmtoll STK_CTRL COUNTFLAG LL_SYSTICK_IsActiveCounterFlag + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SYSTICK_IsActiveCounterFlag(void) +{ + return ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == (SysTick_CTRL_COUNTFLAG_Msk)); +} + +/** + * @brief Configures the SysTick clock source + * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_SetClkSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 + * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK + * @retval None + */ +__STATIC_INLINE void LL_SYSTICK_SetClkSource(uint32_t Source) +{ + if (Source == LL_SYSTICK_CLKSOURCE_HCLK) + { + SET_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); + } + else + { + CLEAR_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); + } +} + +/** + * @brief Get the SysTick clock source + * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_GetClkSource + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 + * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK + */ +__STATIC_INLINE uint32_t LL_SYSTICK_GetClkSource(void) +{ + return READ_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); +} + +/** + * @brief Enable SysTick exception request + * @rmtoll STK_CTRL TICKINT LL_SYSTICK_EnableIT + * @retval None + */ +__STATIC_INLINE void LL_SYSTICK_EnableIT(void) +{ + SET_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); +} + +/** + * @brief Disable SysTick exception request + * @rmtoll STK_CTRL TICKINT LL_SYSTICK_DisableIT + * @retval None + */ +__STATIC_INLINE void LL_SYSTICK_DisableIT(void) +{ + CLEAR_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); +} + +/** + * @brief Checks if the SYSTICK interrupt is enabled or disabled. + * @rmtoll STK_CTRL TICKINT LL_SYSTICK_IsEnabledIT + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SYSTICK_IsEnabledIT(void) +{ + return (READ_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk) == (SysTick_CTRL_TICKINT_Msk)); +} + +/** + * @} + */ + +/** @defgroup CORTEX_LL_EF_LOW_POWER_MODE LOW POWER MODE + * @{ + */ + +/** + * @brief Processor uses sleep as its low power mode + * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableSleep + * @retval None + */ +__STATIC_INLINE void LL_LPM_EnableSleep(void) +{ + /* Clear SLEEPDEEP bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); +} + +/** + * @brief Processor uses deep sleep as its low power mode + * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableDeepSleep + * @retval None + */ +__STATIC_INLINE void LL_LPM_EnableDeepSleep(void) +{ + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); +} + +/** + * @brief Configures sleep-on-exit when returning from Handler mode to Thread mode. + * @note Setting this bit to 1 enables an interrupt-driven application to avoid returning to an + * empty main application. + * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_EnableSleepOnExit + * @retval None + */ +__STATIC_INLINE void LL_LPM_EnableSleepOnExit(void) +{ + /* Set SLEEPONEXIT bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Do not sleep when returning to Thread mode. + * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_DisableSleepOnExit + * @retval None + */ +__STATIC_INLINE void LL_LPM_DisableSleepOnExit(void) +{ + /* Clear SLEEPONEXIT bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Enabled events and all interrupts, including disabled interrupts, can wakeup the + * processor. + * @rmtoll SCB_SCR SEVEONPEND LL_LPM_EnableEventOnPend + * @retval None + */ +__STATIC_INLINE void LL_LPM_EnableEventOnPend(void) +{ + /* Set SEVEONPEND bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @brief Only enabled interrupts or events can wakeup the processor, disabled interrupts are + * excluded + * @rmtoll SCB_SCR SEVEONPEND LL_LPM_DisableEventOnPend + * @retval None + */ +__STATIC_INLINE void LL_LPM_DisableEventOnPend(void) +{ + /* Clear SEVEONPEND bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @} + */ + +/** @defgroup CORTEX_LL_EF_HANDLER HANDLER + * @{ + */ + +/** + * @brief Enable a fault in System handler control register (SHCSR) + * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_EnableFault + * @param Fault This parameter can be a combination of the following values: + * @arg @ref LL_HANDLER_FAULT_USG + * @arg @ref LL_HANDLER_FAULT_BUS + * @arg @ref LL_HANDLER_FAULT_MEM + * @retval None + */ +__STATIC_INLINE void LL_HANDLER_EnableFault(uint32_t Fault) +{ + /* Enable the system handler fault */ + SET_BIT(SCB->SHCSR, Fault); +} + +/** + * @brief Disable a fault in System handler control register (SHCSR) + * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_DisableFault + * @param Fault This parameter can be a combination of the following values: + * @arg @ref LL_HANDLER_FAULT_USG + * @arg @ref LL_HANDLER_FAULT_BUS + * @arg @ref LL_HANDLER_FAULT_MEM + * @retval None + */ +__STATIC_INLINE void LL_HANDLER_DisableFault(uint32_t Fault) +{ + /* Disable the system handler fault */ + CLEAR_BIT(SCB->SHCSR, Fault); +} + +/** + * @} + */ + +/** @defgroup CORTEX_LL_EF_MCU_INFO MCU INFO + * @{ + */ + +/** + * @brief Get Implementer code + * @rmtoll SCB_CPUID IMPLEMENTER LL_CPUID_GetImplementer + * @retval Value should be equal to 0x41 for ARM + */ +__STATIC_INLINE uint32_t LL_CPUID_GetImplementer(void) +{ + return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_IMPLEMENTER_Msk) >> SCB_CPUID_IMPLEMENTER_Pos); +} + +/** + * @brief Get Variant number (The r value in the rnpn product revision identifier) + * @rmtoll SCB_CPUID VARIANT LL_CPUID_GetVariant + * @retval Value between 0 and 255 (0x0: revision 0) + */ +__STATIC_INLINE uint32_t LL_CPUID_GetVariant(void) +{ + return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_VARIANT_Msk) >> SCB_CPUID_VARIANT_Pos); +} + +/** + * @brief Get Constant number + * @rmtoll SCB_CPUID ARCHITECTURE LL_CPUID_GetConstant + * @retval Value should be equal to 0xF for Cortex-M4 devices + */ +__STATIC_INLINE uint32_t LL_CPUID_GetConstant(void) +{ + return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_ARCHITECTURE_Msk) >> SCB_CPUID_ARCHITECTURE_Pos); +} + +/** + * @brief Get Part number + * @rmtoll SCB_CPUID PARTNO LL_CPUID_GetParNo + * @retval Value should be equal to 0xC24 for Cortex-M4 + */ +__STATIC_INLINE uint32_t LL_CPUID_GetParNo(void) +{ + return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_PARTNO_Msk) >> SCB_CPUID_PARTNO_Pos); +} + +/** + * @brief Get Revision number (The p value in the rnpn product revision identifier, indicates patch release) + * @rmtoll SCB_CPUID REVISION LL_CPUID_GetRevision + * @retval Value between 0 and 255 (0x1: patch 1) + */ +__STATIC_INLINE uint32_t LL_CPUID_GetRevision(void) +{ + return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_REVISION_Msk) >> SCB_CPUID_REVISION_Pos); +} + +/** + * @} + */ + +#if __MPU_PRESENT +/** @defgroup CORTEX_LL_EF_MPU MPU + * @{ + */ + +/** + * @brief Enable MPU with input options + * @rmtoll MPU_CTRL ENABLE LL_MPU_Enable + * @param Options This parameter can be one of the following values: + * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF_NONE + * @arg @ref LL_MPU_CTRL_HARDFAULT_NMI + * @arg @ref LL_MPU_CTRL_PRIVILEGED_DEFAULT + * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF + * @retval None + */ +__STATIC_INLINE void LL_MPU_Enable(uint32_t Options) +{ + /* Enable the MPU*/ + WRITE_REG(MPU->CTRL, (MPU_CTRL_ENABLE_Msk | Options)); + /* Ensure MPU settings take effects */ + __DSB(); + /* Sequence instruction fetches using update settings */ + __ISB(); +} + +/** + * @brief Disable MPU + * @rmtoll MPU_CTRL ENABLE LL_MPU_Disable + * @retval None + */ +__STATIC_INLINE void LL_MPU_Disable(void) +{ + /* Make sure outstanding transfers are done */ + __DMB(); + /* Disable MPU*/ + WRITE_REG(MPU->CTRL, 0U); +} + +/** + * @brief Check if MPU is enabled or not + * @rmtoll MPU_CTRL ENABLE LL_MPU_IsEnabled + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_MPU_IsEnabled(void) +{ + return (READ_BIT(MPU->CTRL, MPU_CTRL_ENABLE_Msk) == (MPU_CTRL_ENABLE_Msk)); +} + +/** + * @brief Enable a MPU region + * @rmtoll MPU_RASR ENABLE LL_MPU_EnableRegion + * @param Region This parameter can be one of the following values: + * @arg @ref LL_MPU_REGION_NUMBER0 + * @arg @ref LL_MPU_REGION_NUMBER1 + * @arg @ref LL_MPU_REGION_NUMBER2 + * @arg @ref LL_MPU_REGION_NUMBER3 + * @arg @ref LL_MPU_REGION_NUMBER4 + * @arg @ref LL_MPU_REGION_NUMBER5 + * @arg @ref LL_MPU_REGION_NUMBER6 + * @arg @ref LL_MPU_REGION_NUMBER7 + * @retval None + */ +__STATIC_INLINE void LL_MPU_EnableRegion(uint32_t Region) +{ + /* Set Region number */ + WRITE_REG(MPU->RNR, Region); + /* Enable the MPU region */ + SET_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); +} + +/** + * @brief Configure and enable a region + * @rmtoll MPU_RNR REGION LL_MPU_ConfigRegion\n + * MPU_RBAR REGION LL_MPU_ConfigRegion\n + * MPU_RBAR ADDR LL_MPU_ConfigRegion\n + * MPU_RASR XN LL_MPU_ConfigRegion\n + * MPU_RASR AP LL_MPU_ConfigRegion\n + * MPU_RASR S LL_MPU_ConfigRegion\n + * MPU_RASR C LL_MPU_ConfigRegion\n + * MPU_RASR B LL_MPU_ConfigRegion\n + * MPU_RASR SIZE LL_MPU_ConfigRegion + * @param Region This parameter can be one of the following values: + * @arg @ref LL_MPU_REGION_NUMBER0 + * @arg @ref LL_MPU_REGION_NUMBER1 + * @arg @ref LL_MPU_REGION_NUMBER2 + * @arg @ref LL_MPU_REGION_NUMBER3 + * @arg @ref LL_MPU_REGION_NUMBER4 + * @arg @ref LL_MPU_REGION_NUMBER5 + * @arg @ref LL_MPU_REGION_NUMBER6 + * @arg @ref LL_MPU_REGION_NUMBER7 + * @param Address Value of region base address + * @param SubRegionDisable Sub-region disable value between Min_Data = 0x00 and Max_Data = 0xFF + * @param Attributes This parameter can be a combination of the following values: + * @arg @ref LL_MPU_REGION_SIZE_32B or @ref LL_MPU_REGION_SIZE_64B or @ref LL_MPU_REGION_SIZE_128B or @ref LL_MPU_REGION_SIZE_256B or @ref LL_MPU_REGION_SIZE_512B + * or @ref LL_MPU_REGION_SIZE_1KB or @ref LL_MPU_REGION_SIZE_2KB or @ref LL_MPU_REGION_SIZE_4KB or @ref LL_MPU_REGION_SIZE_8KB or @ref LL_MPU_REGION_SIZE_16KB + * or @ref LL_MPU_REGION_SIZE_32KB or @ref LL_MPU_REGION_SIZE_64KB or @ref LL_MPU_REGION_SIZE_128KB or @ref LL_MPU_REGION_SIZE_256KB or @ref LL_MPU_REGION_SIZE_512KB + * or @ref LL_MPU_REGION_SIZE_1MB or @ref LL_MPU_REGION_SIZE_2MB or @ref LL_MPU_REGION_SIZE_4MB or @ref LL_MPU_REGION_SIZE_8MB or @ref LL_MPU_REGION_SIZE_16MB + * or @ref LL_MPU_REGION_SIZE_32MB or @ref LL_MPU_REGION_SIZE_64MB or @ref LL_MPU_REGION_SIZE_128MB or @ref LL_MPU_REGION_SIZE_256MB or @ref LL_MPU_REGION_SIZE_512MB + * or @ref LL_MPU_REGION_SIZE_1GB or @ref LL_MPU_REGION_SIZE_2GB or @ref LL_MPU_REGION_SIZE_4GB + * @arg @ref LL_MPU_REGION_NO_ACCESS or @ref LL_MPU_REGION_PRIV_RW or @ref LL_MPU_REGION_PRIV_RW_URO or @ref LL_MPU_REGION_FULL_ACCESS + * or @ref LL_MPU_REGION_PRIV_RO or @ref LL_MPU_REGION_PRIV_RO_URO + * @arg @ref LL_MPU_TEX_LEVEL0 or @ref LL_MPU_TEX_LEVEL1 or @ref LL_MPU_TEX_LEVEL2 or @ref LL_MPU_TEX_LEVEL4 + * @arg @ref LL_MPU_INSTRUCTION_ACCESS_ENABLE or @ref LL_MPU_INSTRUCTION_ACCESS_DISABLE + * @arg @ref LL_MPU_ACCESS_SHAREABLE or @ref LL_MPU_ACCESS_NOT_SHAREABLE + * @arg @ref LL_MPU_ACCESS_CACHEABLE or @ref LL_MPU_ACCESS_NOT_CACHEABLE + * @arg @ref LL_MPU_ACCESS_BUFFERABLE or @ref LL_MPU_ACCESS_NOT_BUFFERABLE + * @retval None + */ +__STATIC_INLINE void LL_MPU_ConfigRegion(uint32_t Region, uint32_t SubRegionDisable, uint32_t Address, uint32_t Attributes) +{ + /* Set Region number */ + WRITE_REG(MPU->RNR, Region); + /* Set base address */ + WRITE_REG(MPU->RBAR, (Address & 0xFFFFFFE0U)); + /* Configure MPU */ + WRITE_REG(MPU->RASR, (MPU_RASR_ENABLE_Msk | Attributes | SubRegionDisable << MPU_RASR_SRD_Pos)); +} + +/** + * @brief Disable a region + * @rmtoll MPU_RNR REGION LL_MPU_DisableRegion\n + * MPU_RASR ENABLE LL_MPU_DisableRegion + * @param Region This parameter can be one of the following values: + * @arg @ref LL_MPU_REGION_NUMBER0 + * @arg @ref LL_MPU_REGION_NUMBER1 + * @arg @ref LL_MPU_REGION_NUMBER2 + * @arg @ref LL_MPU_REGION_NUMBER3 + * @arg @ref LL_MPU_REGION_NUMBER4 + * @arg @ref LL_MPU_REGION_NUMBER5 + * @arg @ref LL_MPU_REGION_NUMBER6 + * @arg @ref LL_MPU_REGION_NUMBER7 + * @retval None + */ +__STATIC_INLINE void LL_MPU_DisableRegion(uint32_t Region) +{ + /* Set Region number */ + WRITE_REG(MPU->RNR, Region); + /* Disable the MPU region */ + CLEAR_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); +} + +/** + * @} + */ + +#endif /* __MPU_PRESENT */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_CORTEX_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h index 76444fc..c04ac76 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h @@ -1,2868 +1,2868 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma.h - * @author MCD Application Team - * @brief Header file of DMA LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_DMA_H -#define __STM32F4xx_LL_DMA_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA1) || defined (DMA2) - -/** @defgroup DMA_LL DMA - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Variables DMA Private Variables - * @{ - */ -/* Array used to get the DMA stream register offset versus stream index LL_DMA_STREAM_x */ -static const uint8_t STREAM_OFFSET_TAB[] = -{ - (uint8_t)(DMA1_Stream0_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream1_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream2_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream3_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream4_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream5_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream6_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream7_BASE - DMA1_BASE) -}; - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Constants DMA Private Constants - * @{ - */ -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_ES_INIT DMA Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeriphOrM2MSrcAddress; /*!< Specifies the peripheral base address for DMA transfer - or as Source base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t MemoryOrM2MDstAddress; /*!< Specifies the memory base address for DMA transfer - or as Destination base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_LL_EC_DIRECTION - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataTransferDirection(). */ - - uint32_t Mode; /*!< Specifies the normal or circular operation mode. - This parameter can be a value of @ref DMA_LL_EC_MODE - @note The circular buffer mode cannot be used if the memory to memory - data transfer direction is configured on the selected Stream - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMode(). */ - - uint32_t PeriphOrM2MSrcIncMode; /*!< Specifies whether the Peripheral address or Source address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_PERIPH - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphIncMode(). */ - - uint32_t MemoryOrM2MDstIncMode; /*!< Specifies whether the Memory address or Destination address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_MEMORY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryIncMode(). */ - - uint32_t PeriphOrM2MSrcDataSize; /*!< Specifies the Peripheral data size alignment or Source data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_PDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphSize(). */ - - uint32_t MemoryOrM2MDstDataSize; /*!< Specifies the Memory data size alignment or Destination data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_MDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemorySize(). */ - - uint32_t NbData; /*!< Specifies the number of data to transfer, in data unit. - The data unit is equal to the source buffer configuration set in PeripheralSize - or MemorySize parameters depending in the transfer direction. - This parameter must be a value between Min_Data = 0 and Max_Data = 0x0000FFFF - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataLength(). */ - - uint32_t Channel; /*!< Specifies the peripheral channel. - This parameter can be a value of @ref DMA_LL_EC_CHANNEL - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetChannelSelection(). */ - - uint32_t Priority; /*!< Specifies the channel priority level. - This parameter can be a value of @ref DMA_LL_EC_PRIORITY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetStreamPriorityLevel(). */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_LL_FIFOMODE - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream - - This feature can be modified afterwards using unitary functions @ref LL_DMA_EnableFifoMode() or @ref LL_DMA_EnableFifoMode() . */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_LL_EC_FIFOTHRESHOLD - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetFIFOThreshold(). */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_MBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryBurstxfer(). */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_PBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphBurstxfer(). */ - -} LL_DMA_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Constants DMA Exported Constants - * @{ - */ - -/** @defgroup DMA_LL_EC_STREAM STREAM - * @{ - */ -#define LL_DMA_STREAM_0 0x00000000U -#define LL_DMA_STREAM_1 0x00000001U -#define LL_DMA_STREAM_2 0x00000002U -#define LL_DMA_STREAM_3 0x00000003U -#define LL_DMA_STREAM_4 0x00000004U -#define LL_DMA_STREAM_5 0x00000005U -#define LL_DMA_STREAM_6 0x00000006U -#define LL_DMA_STREAM_7 0x00000007U -#define LL_DMA_STREAM_ALL 0xFFFF0000U -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DIRECTION DIRECTION - * @{ - */ -#define LL_DMA_DIRECTION_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_PERIPH DMA_SxCR_DIR_0 /*!< Memory to peripheral direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_MEMORY DMA_SxCR_DIR_1 /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MODE MODE - * @{ - */ -#define LL_DMA_MODE_NORMAL 0x00000000U /*!< Normal Mode */ -#define LL_DMA_MODE_CIRCULAR DMA_SxCR_CIRC /*!< Circular Mode */ -#define LL_DMA_MODE_PFCTRL DMA_SxCR_PFCTRL /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DOUBLEBUFFER_MODE DOUBLEBUFFER MODE - * @{ - */ -#define LL_DMA_DOUBLEBUFFER_MODE_DISABLE 0x00000000U /*!< Disable double buffering mode */ -#define LL_DMA_DOUBLEBUFFER_MODE_ENABLE DMA_SxCR_DBM /*!< Enable double buffering mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PERIPH PERIPH - * @{ - */ -#define LL_DMA_PERIPH_NOINCREMENT 0x00000000U /*!< Peripheral increment mode Disable */ -#define LL_DMA_PERIPH_INCREMENT DMA_SxCR_PINC /*!< Peripheral increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MEMORY MEMORY - * @{ - */ -#define LL_DMA_MEMORY_NOINCREMENT 0x00000000U /*!< Memory increment mode Disable */ -#define LL_DMA_MEMORY_INCREMENT DMA_SxCR_MINC /*!< Memory increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PDATAALIGN PDATAALIGN - * @{ - */ -#define LL_DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment : Byte */ -#define LL_DMA_PDATAALIGN_HALFWORD DMA_SxCR_PSIZE_0 /*!< Peripheral data alignment : HalfWord */ -#define LL_DMA_PDATAALIGN_WORD DMA_SxCR_PSIZE_1 /*!< Peripheral data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MDATAALIGN MDATAALIGN - * @{ - */ -#define LL_DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment : Byte */ -#define LL_DMA_MDATAALIGN_HALFWORD DMA_SxCR_MSIZE_0 /*!< Memory data alignment : HalfWord */ -#define LL_DMA_MDATAALIGN_WORD DMA_SxCR_MSIZE_1 /*!< Memory data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_OFFSETSIZE OFFSETSIZE - * @{ - */ -#define LL_DMA_OFFSETSIZE_PSIZE 0x00000000U /*!< Peripheral increment offset size is linked to the PSIZE */ -#define LL_DMA_OFFSETSIZE_FIXEDTO4 DMA_SxCR_PINCOS /*!< Peripheral increment offset size is fixed to 4 (32-bit alignment) */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PRIORITY PRIORITY - * @{ - */ -#define LL_DMA_PRIORITY_LOW 0x00000000U /*!< Priority level : Low */ -#define LL_DMA_PRIORITY_MEDIUM DMA_SxCR_PL_0 /*!< Priority level : Medium */ -#define LL_DMA_PRIORITY_HIGH DMA_SxCR_PL_1 /*!< Priority level : High */ -#define LL_DMA_PRIORITY_VERYHIGH DMA_SxCR_PL /*!< Priority level : Very_High */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CHANNEL CHANNEL - * @{ - */ -#define LL_DMA_CHANNEL_0 0x00000000U /* Select Channel0 of DMA Instance */ -#define LL_DMA_CHANNEL_1 DMA_SxCR_CHSEL_0 /* Select Channel1 of DMA Instance */ -#define LL_DMA_CHANNEL_2 DMA_SxCR_CHSEL_1 /* Select Channel2 of DMA Instance */ -#define LL_DMA_CHANNEL_3 (DMA_SxCR_CHSEL_0 | DMA_SxCR_CHSEL_1) /* Select Channel3 of DMA Instance */ -#define LL_DMA_CHANNEL_4 DMA_SxCR_CHSEL_2 /* Select Channel4 of DMA Instance */ -#define LL_DMA_CHANNEL_5 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel5 of DMA Instance */ -#define LL_DMA_CHANNEL_6 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel6 of DMA Instance */ -#define LL_DMA_CHANNEL_7 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel7 of DMA Instance */ -#if defined (DMA_SxCR_CHSEL_3) -#define LL_DMA_CHANNEL_8 DMA_SxCR_CHSEL_3 /* Select Channel8 of DMA Instance */ -#define LL_DMA_CHANNEL_9 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_0) /* Select Channel9 of DMA Instance */ -#define LL_DMA_CHANNEL_10 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1) /* Select Channel10 of DMA Instance */ -#define LL_DMA_CHANNEL_11 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel11 of DMA Instance */ -#define LL_DMA_CHANNEL_12 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2) /* Select Channel12 of DMA Instance */ -#define LL_DMA_CHANNEL_13 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel13 of DMA Instance */ -#define LL_DMA_CHANNEL_14 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel14 of DMA Instance */ -#define LL_DMA_CHANNEL_15 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel15 of DMA Instance */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MBURST MBURST - * @{ - */ -#define LL_DMA_MBURST_SINGLE 0x00000000U /*!< Memory burst single transfer configuration */ -#define LL_DMA_MBURST_INC4 DMA_SxCR_MBURST_0 /*!< Memory burst of 4 beats transfer configuration */ -#define LL_DMA_MBURST_INC8 DMA_SxCR_MBURST_1 /*!< Memory burst of 8 beats transfer configuration */ -#define LL_DMA_MBURST_INC16 (DMA_SxCR_MBURST_0 | DMA_SxCR_MBURST_1) /*!< Memory burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PBURST PBURST - * @{ - */ -#define LL_DMA_PBURST_SINGLE 0x00000000U /*!< Peripheral burst single transfer configuration */ -#define LL_DMA_PBURST_INC4 DMA_SxCR_PBURST_0 /*!< Peripheral burst of 4 beats transfer configuration */ -#define LL_DMA_PBURST_INC8 DMA_SxCR_PBURST_1 /*!< Peripheral burst of 8 beats transfer configuration */ -#define LL_DMA_PBURST_INC16 (DMA_SxCR_PBURST_0 | DMA_SxCR_PBURST_1) /*!< Peripheral burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_FIFOMODE DMA_LL_FIFOMODE - * @{ - */ -#define LL_DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable (direct mode is enabled) */ -#define LL_DMA_FIFOMODE_ENABLE DMA_SxFCR_DMDIS /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOSTATUS_0 FIFOSTATUS 0 - * @{ - */ -#define LL_DMA_FIFOSTATUS_0_25 0x00000000U /*!< 0 < fifo_level < 1/4 */ -#define LL_DMA_FIFOSTATUS_25_50 DMA_SxFCR_FS_0 /*!< 1/4 < fifo_level < 1/2 */ -#define LL_DMA_FIFOSTATUS_50_75 DMA_SxFCR_FS_1 /*!< 1/2 < fifo_level < 3/4 */ -#define LL_DMA_FIFOSTATUS_75_100 (DMA_SxFCR_FS_1 | DMA_SxFCR_FS_0) /*!< 3/4 < fifo_level < full */ -#define LL_DMA_FIFOSTATUS_EMPTY DMA_SxFCR_FS_2 /*!< FIFO is empty */ -#define LL_DMA_FIFOSTATUS_FULL (DMA_SxFCR_FS_2 | DMA_SxFCR_FS_0) /*!< FIFO is full */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOTHRESHOLD FIFOTHRESHOLD - * @{ - */ -#define LL_DMA_FIFOTHRESHOLD_1_4 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define LL_DMA_FIFOTHRESHOLD_1_2 DMA_SxFCR_FTH_0 /*!< FIFO threshold half full configuration */ -#define LL_DMA_FIFOTHRESHOLD_3_4 DMA_SxFCR_FTH_1 /*!< FIFO threshold 3 quarts full configuration */ -#define LL_DMA_FIFOTHRESHOLD_FULL DMA_SxFCR_FTH /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CURRENTTARGETMEM CURRENTTARGETMEM - * @{ - */ -#define LL_DMA_CURRENTTARGETMEM0 0x00000000U /*!< Set CurrentTarget Memory to Memory 0 */ -#define LL_DMA_CURRENTTARGETMEM1 DMA_SxCR_CT /*!< Set CurrentTarget Memory to Memory 1 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Macros DMA Exported Macros - * @{ - */ - -/** @defgroup DMA_LL_EM_WRITE_READ Common Write and read registers macros - * @{ - */ -/** - * @brief Write a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DMA_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DMA_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup DMA_LL_EM_CONVERT_DMAxCHANNELy Convert DMAxStreamy - * @{ - */ -/** - * @brief Convert DMAx_Streamy into DMAx - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval DMAx - */ -#define __LL_DMA_GET_INSTANCE(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) > ((uint32_t)DMA1_Stream7)) ? DMA2 : DMA1) - -/** - * @brief Convert DMAx_Streamy into LL_DMA_STREAM_y - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval LL_DMA_CHANNEL_y - */ -#define __LL_DMA_GET_STREAM(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream6)) ? LL_DMA_STREAM_6 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream6)) ? LL_DMA_STREAM_6 : \ - LL_DMA_STREAM_7) - -/** - * @brief Convert DMA Instance DMAx and LL_DMA_STREAM_y into DMAx_Streamy - * @param __DMA_INSTANCE__ DMAx - * @param __STREAM__ LL_DMA_STREAM_y - * @retval DMAx_Streamy - */ -#define __LL_DMA_GET_STREAM_INSTANCE(__DMA_INSTANCE__, __STREAM__) \ -((((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA1_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA2_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA1_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA2_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA1_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA2_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA1_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA2_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA1_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA2_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA1_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA2_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA1_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA2_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_7))) ? DMA1_Stream7 : \ - DMA2_Stream7) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ - /** @defgroup DMA_LL_Exported_Functions DMA Exported Functions - * @{ - */ - -/** @defgroup DMA_LL_EF_Configuration Configuration - * @{ - */ -/** - * @brief Enable DMA stream. - * @rmtoll CR EN LL_DMA_EnableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Disable DMA stream. - * @rmtoll CR EN LL_DMA_DisableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Check if DMA stream is enabled or disabled. - * @rmtoll CR EN LL_DMA_IsEnabledStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN) == (DMA_SxCR_EN)); -} - -/** - * @brief Configure all parameters linked to DMA transfer. - * @rmtoll CR DIR LL_DMA_ConfigTransfer\n - * CR CIRC LL_DMA_ConfigTransfer\n - * CR PINC LL_DMA_ConfigTransfer\n - * CR MINC LL_DMA_ConfigTransfer\n - * CR PSIZE LL_DMA_ConfigTransfer\n - * CR MSIZE LL_DMA_ConfigTransfer\n - * CR PL LL_DMA_ConfigTransfer\n - * CR PFCTRL LL_DMA_ConfigTransfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY or @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH or @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @arg @ref LL_DMA_MODE_NORMAL or @ref LL_DMA_MODE_CIRCULAR or @ref LL_DMA_MODE_PFCTRL - * @arg @ref LL_DMA_PERIPH_INCREMENT or @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT or @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_PDATAALIGN_BYTE or @ref LL_DMA_PDATAALIGN_HALFWORD or @ref LL_DMA_PDATAALIGN_WORD - * @arg @ref LL_DMA_MDATAALIGN_BYTE or @ref LL_DMA_MDATAALIGN_HALFWORD or @ref LL_DMA_MDATAALIGN_WORD - * @arg @ref LL_DMA_PRIORITY_LOW or @ref LL_DMA_PRIORITY_MEDIUM or @ref LL_DMA_PRIORITY_HIGH or @ref LL_DMA_PRIORITY_VERYHIGH - *@retval None - */ -__STATIC_INLINE void LL_DMA_ConfigTransfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Configuration) -{ - MODIFY_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, - DMA_SxCR_DIR | DMA_SxCR_CIRC | DMA_SxCR_PINC | DMA_SxCR_MINC | DMA_SxCR_PSIZE | DMA_SxCR_MSIZE | DMA_SxCR_PL | DMA_SxCR_PFCTRL, - Configuration); -} - -/** - * @brief Set Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_SetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Direction) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR, Direction); -} - -/** - * @brief Get Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_GetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR)); -} - -/** - * @brief Set DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_SetMode\n - * CR PFCTRL LL_DMA_SetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL, Mode); -} - -/** - * @brief Get DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_GetMode\n - * CR PFCTRL LL_DMA_GetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - */ -__STATIC_INLINE uint32_t LL_DMA_GetMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL)); -} - -/** - * @brief Set Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_SetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC, IncrementMode); -} - -/** - * @brief Get Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_GetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC)); -} - -/** - * @brief Set Memory increment mode. - * @rmtoll CR MINC LL_DMA_SetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC, IncrementMode); -} - -/** - * @brief Get Memory increment mode. - * @rmtoll CR MINC LL_DMA_GetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC)); -} - -/** - * @brief Set Peripheral size. - * @rmtoll CR PSIZE LL_DMA_SetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE, Size); -} - -/** - * @brief Get Peripheral size. - * @rmtoll CR PSIZE LL_DMA_GetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE)); -} - -/** - * @brief Set Memory size. - * @rmtoll CR MSIZE LL_DMA_SetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE, Size); -} - -/** - * @brief Get Memory size. - * @rmtoll CR MSIZE LL_DMA_GetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE)); -} - -/** - * @brief Set Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_SetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param OffsetSize This parameter can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t OffsetSize) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS, OffsetSize); -} - -/** - * @brief Get Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_GetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - */ -__STATIC_INLINE uint32_t LL_DMA_GetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS)); -} - -/** - * @brief Set Stream priority level. - * @rmtoll CR PL LL_DMA_SetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Priority This parameter can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Priority) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL, Priority); -} - -/** - * @brief Get Stream priority level. - * @rmtoll CR PL LL_DMA_GetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - */ -__STATIC_INLINE uint32_t LL_DMA_GetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL)); -} - -/** - * @brief Set Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_SetDataLength - * @note This action has no effect if - * stream is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param NbData Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataLength(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t NbData) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT, NbData); -} - -/** - * @brief Get Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_GetDataLength - * @note Once the stream is enabled, the return value indicate the - * remaining bytes to be transmitted. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataLength(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT)); -} - -/** - * @brief Select Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_SetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Channel) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL, Channel); -} - -/** - * @brief Get the Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_GetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - */ -__STATIC_INLINE uint32_t LL_DMA_GetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL)); -} - -/** - * @brief Set Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_SetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mburst This parameter can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST, Mburst); -} - -/** - * @brief Get Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_GetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST)); -} - -/** - * @brief Set Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_SetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Pburst This parameter can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Pburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST, Pburst); -} - -/** - * @brief Get Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_GetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST)); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_SetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param CurrentMemory This parameter can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t CurrentMemory) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT, CurrentMemory); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_GetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - */ -__STATIC_INLINE uint32_t LL_DMA_GetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT)); -} - -/** - * @brief Enable the double buffer mode. - * @rmtoll CR DBM LL_DMA_EnableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Disable the double buffer mode. - * @rmtoll CR DBM LL_DMA_DisableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Get FIFO status. - * @rmtoll FCR FS LL_DMA_GetFIFOStatus - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOSTATUS_0_25 - * @arg @ref LL_DMA_FIFOSTATUS_25_50 - * @arg @ref LL_DMA_FIFOSTATUS_50_75 - * @arg @ref LL_DMA_FIFOSTATUS_75_100 - * @arg @ref LL_DMA_FIFOSTATUS_EMPTY - * @arg @ref LL_DMA_FIFOSTATUS_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOStatus(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FS)); -} - -/** - * @brief Disable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_DisableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Enable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_EnableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Select FIFO threshold. - * @rmtoll FCR FTH LL_DMA_SetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Threshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Threshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH, Threshold); -} - -/** - * @brief Get FIFO threshold. - * @rmtoll FCR FTH LL_DMA_GetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH)); -} - -/** - * @brief Configure the FIFO . - * @rmtoll FCR FTH LL_DMA_ConfigFifo\n - * FCR DMDIS LL_DMA_ConfigFifo - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param FifoMode This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOMODE_ENABLE - * @arg @ref LL_DMA_FIFOMODE_DISABLE - * @param FifoThreshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigFifo(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t FifoMode, uint32_t FifoThreshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH|DMA_SxFCR_DMDIS, FifoMode|FifoThreshold); -} - -/** - * @brief Configure the Source and Destination addresses. - * @note This API must not be called when the DMA stream is enabled. - * @rmtoll M0AR M0A LL_DMA_ConfigAddresses\n - * PAR PA LL_DMA_ConfigAddresses - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param SrcAddress Between 0 to 0xFFFFFFFF - * @param DstAddress Between 0 to 0xFFFFFFFF - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigAddresses(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t SrcAddress, uint32_t DstAddress, uint32_t Direction) -{ - /* Direction Memory to Periph */ - if (Direction == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, DstAddress); - } - /* Direction Periph to Memory and Memory to Memory */ - else - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, DstAddress); - } -} - -/** - * @brief Set the Memory address. - * @rmtoll M0AR M0A LL_DMA_SetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); -} - -/** - * @brief Set the Peripheral address. - * @rmtoll PAR PA LL_DMA_SetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param PeriphAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t PeriphAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, PeriphAddress); -} - -/** - * @brief Get the Memory address. - * @rmtoll M0AR M0A LL_DMA_GetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Get the Peripheral address. - * @rmtoll PAR PA LL_DMA_GetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); -} - -/** - * @brief Set the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_SetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, MemoryAddress); -} - -/** - * @brief Set the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_SetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); - } - -/** - * @brief Get the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_GetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream) - { - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); - } - -/** - * @brief Get the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_GetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Set Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_SetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Address Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Address) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR, DMA_SxM1AR_M1A, Address); -} - -/** - * @brief Get Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_GetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Stream 0 half transfer flag. - * @rmtoll LISR HTIF0 LL_DMA_IsActiveFlag_HT0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF0)==(DMA_LISR_HTIF0)); -} - -/** - * @brief Get Stream 1 half transfer flag. - * @rmtoll LISR HTIF1 LL_DMA_IsActiveFlag_HT1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF1)==(DMA_LISR_HTIF1)); -} - -/** - * @brief Get Stream 2 half transfer flag. - * @rmtoll LISR HTIF2 LL_DMA_IsActiveFlag_HT2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF2)==(DMA_LISR_HTIF2)); -} - -/** - * @brief Get Stream 3 half transfer flag. - * @rmtoll LISR HTIF3 LL_DMA_IsActiveFlag_HT3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF3)==(DMA_LISR_HTIF3)); -} - -/** - * @brief Get Stream 4 half transfer flag. - * @rmtoll HISR HTIF4 LL_DMA_IsActiveFlag_HT4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF4)==(DMA_HISR_HTIF4)); -} - -/** - * @brief Get Stream 5 half transfer flag. - * @rmtoll HISR HTIF0 LL_DMA_IsActiveFlag_HT5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF5)==(DMA_HISR_HTIF5)); -} - -/** - * @brief Get Stream 6 half transfer flag. - * @rmtoll HISR HTIF6 LL_DMA_IsActiveFlag_HT6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF6)==(DMA_HISR_HTIF6)); -} - -/** - * @brief Get Stream 7 half transfer flag. - * @rmtoll HISR HTIF7 LL_DMA_IsActiveFlag_HT7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF7)==(DMA_HISR_HTIF7)); -} - -/** - * @brief Get Stream 0 transfer complete flag. - * @rmtoll LISR TCIF0 LL_DMA_IsActiveFlag_TC0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF0)==(DMA_LISR_TCIF0)); -} - -/** - * @brief Get Stream 1 transfer complete flag. - * @rmtoll LISR TCIF1 LL_DMA_IsActiveFlag_TC1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF1)==(DMA_LISR_TCIF1)); -} - -/** - * @brief Get Stream 2 transfer complete flag. - * @rmtoll LISR TCIF2 LL_DMA_IsActiveFlag_TC2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF2)==(DMA_LISR_TCIF2)); -} - -/** - * @brief Get Stream 3 transfer complete flag. - * @rmtoll LISR TCIF3 LL_DMA_IsActiveFlag_TC3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF3)==(DMA_LISR_TCIF3)); -} - -/** - * @brief Get Stream 4 transfer complete flag. - * @rmtoll HISR TCIF4 LL_DMA_IsActiveFlag_TC4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF4)==(DMA_HISR_TCIF4)); -} - -/** - * @brief Get Stream 5 transfer complete flag. - * @rmtoll HISR TCIF0 LL_DMA_IsActiveFlag_TC5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF5)==(DMA_HISR_TCIF5)); -} - -/** - * @brief Get Stream 6 transfer complete flag. - * @rmtoll HISR TCIF6 LL_DMA_IsActiveFlag_TC6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF6)==(DMA_HISR_TCIF6)); -} - -/** - * @brief Get Stream 7 transfer complete flag. - * @rmtoll HISR TCIF7 LL_DMA_IsActiveFlag_TC7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF7)==(DMA_HISR_TCIF7)); -} - -/** - * @brief Get Stream 0 transfer error flag. - * @rmtoll LISR TEIF0 LL_DMA_IsActiveFlag_TE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF0)==(DMA_LISR_TEIF0)); -} - -/** - * @brief Get Stream 1 transfer error flag. - * @rmtoll LISR TEIF1 LL_DMA_IsActiveFlag_TE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF1)==(DMA_LISR_TEIF1)); -} - -/** - * @brief Get Stream 2 transfer error flag. - * @rmtoll LISR TEIF2 LL_DMA_IsActiveFlag_TE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF2)==(DMA_LISR_TEIF2)); -} - -/** - * @brief Get Stream 3 transfer error flag. - * @rmtoll LISR TEIF3 LL_DMA_IsActiveFlag_TE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF3)==(DMA_LISR_TEIF3)); -} - -/** - * @brief Get Stream 4 transfer error flag. - * @rmtoll HISR TEIF4 LL_DMA_IsActiveFlag_TE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF4)==(DMA_HISR_TEIF4)); -} - -/** - * @brief Get Stream 5 transfer error flag. - * @rmtoll HISR TEIF0 LL_DMA_IsActiveFlag_TE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF5)==(DMA_HISR_TEIF5)); -} - -/** - * @brief Get Stream 6 transfer error flag. - * @rmtoll HISR TEIF6 LL_DMA_IsActiveFlag_TE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF6)==(DMA_HISR_TEIF6)); -} - -/** - * @brief Get Stream 7 transfer error flag. - * @rmtoll HISR TEIF7 LL_DMA_IsActiveFlag_TE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF7)==(DMA_HISR_TEIF7)); -} - -/** - * @brief Get Stream 0 direct mode error flag. - * @rmtoll LISR DMEIF0 LL_DMA_IsActiveFlag_DME0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF0)==(DMA_LISR_DMEIF0)); -} - -/** - * @brief Get Stream 1 direct mode error flag. - * @rmtoll LISR DMEIF1 LL_DMA_IsActiveFlag_DME1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF1)==(DMA_LISR_DMEIF1)); -} - -/** - * @brief Get Stream 2 direct mode error flag. - * @rmtoll LISR DMEIF2 LL_DMA_IsActiveFlag_DME2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF2)==(DMA_LISR_DMEIF2)); -} - -/** - * @brief Get Stream 3 direct mode error flag. - * @rmtoll LISR DMEIF3 LL_DMA_IsActiveFlag_DME3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF3)==(DMA_LISR_DMEIF3)); -} - -/** - * @brief Get Stream 4 direct mode error flag. - * @rmtoll HISR DMEIF4 LL_DMA_IsActiveFlag_DME4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF4)==(DMA_HISR_DMEIF4)); -} - -/** - * @brief Get Stream 5 direct mode error flag. - * @rmtoll HISR DMEIF0 LL_DMA_IsActiveFlag_DME5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF5)==(DMA_HISR_DMEIF5)); -} - -/** - * @brief Get Stream 6 direct mode error flag. - * @rmtoll HISR DMEIF6 LL_DMA_IsActiveFlag_DME6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF6)==(DMA_HISR_DMEIF6)); -} - -/** - * @brief Get Stream 7 direct mode error flag. - * @rmtoll HISR DMEIF7 LL_DMA_IsActiveFlag_DME7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF7)==(DMA_HISR_DMEIF7)); -} - -/** - * @brief Get Stream 0 FIFO error flag. - * @rmtoll LISR FEIF0 LL_DMA_IsActiveFlag_FE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF0)==(DMA_LISR_FEIF0)); -} - -/** - * @brief Get Stream 1 FIFO error flag. - * @rmtoll LISR FEIF1 LL_DMA_IsActiveFlag_FE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF1)==(DMA_LISR_FEIF1)); -} - -/** - * @brief Get Stream 2 FIFO error flag. - * @rmtoll LISR FEIF2 LL_DMA_IsActiveFlag_FE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF2)==(DMA_LISR_FEIF2)); -} - -/** - * @brief Get Stream 3 FIFO error flag. - * @rmtoll LISR FEIF3 LL_DMA_IsActiveFlag_FE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF3)==(DMA_LISR_FEIF3)); -} - -/** - * @brief Get Stream 4 FIFO error flag. - * @rmtoll HISR FEIF4 LL_DMA_IsActiveFlag_FE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF4)==(DMA_HISR_FEIF4)); -} - -/** - * @brief Get Stream 5 FIFO error flag. - * @rmtoll HISR FEIF0 LL_DMA_IsActiveFlag_FE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF5)==(DMA_HISR_FEIF5)); -} - -/** - * @brief Get Stream 6 FIFO error flag. - * @rmtoll HISR FEIF6 LL_DMA_IsActiveFlag_FE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF6)==(DMA_HISR_FEIF6)); -} - -/** - * @brief Get Stream 7 FIFO error flag. - * @rmtoll HISR FEIF7 LL_DMA_IsActiveFlag_FE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF7)==(DMA_HISR_FEIF7)); -} - -/** - * @brief Clear Stream 0 half transfer flag. - * @rmtoll LIFCR CHTIF0 LL_DMA_ClearFlag_HT0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF0); -} - -/** - * @brief Clear Stream 1 half transfer flag. - * @rmtoll LIFCR CHTIF1 LL_DMA_ClearFlag_HT1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF1); -} - -/** - * @brief Clear Stream 2 half transfer flag. - * @rmtoll LIFCR CHTIF2 LL_DMA_ClearFlag_HT2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF2); -} - -/** - * @brief Clear Stream 3 half transfer flag. - * @rmtoll LIFCR CHTIF3 LL_DMA_ClearFlag_HT3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF3); -} - -/** - * @brief Clear Stream 4 half transfer flag. - * @rmtoll HIFCR CHTIF4 LL_DMA_ClearFlag_HT4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF4); -} - -/** - * @brief Clear Stream 5 half transfer flag. - * @rmtoll HIFCR CHTIF5 LL_DMA_ClearFlag_HT5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF5); -} - -/** - * @brief Clear Stream 6 half transfer flag. - * @rmtoll HIFCR CHTIF6 LL_DMA_ClearFlag_HT6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF6); -} - -/** - * @brief Clear Stream 7 half transfer flag. - * @rmtoll HIFCR CHTIF7 LL_DMA_ClearFlag_HT7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF7); -} - -/** - * @brief Clear Stream 0 transfer complete flag. - * @rmtoll LIFCR CTCIF0 LL_DMA_ClearFlag_TC0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF0); -} - -/** - * @brief Clear Stream 1 transfer complete flag. - * @rmtoll LIFCR CTCIF1 LL_DMA_ClearFlag_TC1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF1); -} - -/** - * @brief Clear Stream 2 transfer complete flag. - * @rmtoll LIFCR CTCIF2 LL_DMA_ClearFlag_TC2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF2); -} - -/** - * @brief Clear Stream 3 transfer complete flag. - * @rmtoll LIFCR CTCIF3 LL_DMA_ClearFlag_TC3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF3); -} - -/** - * @brief Clear Stream 4 transfer complete flag. - * @rmtoll HIFCR CTCIF4 LL_DMA_ClearFlag_TC4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF4); -} - -/** - * @brief Clear Stream 5 transfer complete flag. - * @rmtoll HIFCR CTCIF5 LL_DMA_ClearFlag_TC5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF5); -} - -/** - * @brief Clear Stream 6 transfer complete flag. - * @rmtoll HIFCR CTCIF6 LL_DMA_ClearFlag_TC6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF6); -} - -/** - * @brief Clear Stream 7 transfer complete flag. - * @rmtoll HIFCR CTCIF7 LL_DMA_ClearFlag_TC7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF7); -} - -/** - * @brief Clear Stream 0 transfer error flag. - * @rmtoll LIFCR CTEIF0 LL_DMA_ClearFlag_TE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF0); -} - -/** - * @brief Clear Stream 1 transfer error flag. - * @rmtoll LIFCR CTEIF1 LL_DMA_ClearFlag_TE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF1); -} - -/** - * @brief Clear Stream 2 transfer error flag. - * @rmtoll LIFCR CTEIF2 LL_DMA_ClearFlag_TE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF2); -} - -/** - * @brief Clear Stream 3 transfer error flag. - * @rmtoll LIFCR CTEIF3 LL_DMA_ClearFlag_TE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF3); -} - -/** - * @brief Clear Stream 4 transfer error flag. - * @rmtoll HIFCR CTEIF4 LL_DMA_ClearFlag_TE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF4); -} - -/** - * @brief Clear Stream 5 transfer error flag. - * @rmtoll HIFCR CTEIF5 LL_DMA_ClearFlag_TE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF5); -} - -/** - * @brief Clear Stream 6 transfer error flag. - * @rmtoll HIFCR CTEIF6 LL_DMA_ClearFlag_TE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF6); -} - -/** - * @brief Clear Stream 7 transfer error flag. - * @rmtoll HIFCR CTEIF7 LL_DMA_ClearFlag_TE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF7); -} - -/** - * @brief Clear Stream 0 direct mode error flag. - * @rmtoll LIFCR CDMEIF0 LL_DMA_ClearFlag_DME0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF0); -} - -/** - * @brief Clear Stream 1 direct mode error flag. - * @rmtoll LIFCR CDMEIF1 LL_DMA_ClearFlag_DME1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF1); -} - -/** - * @brief Clear Stream 2 direct mode error flag. - * @rmtoll LIFCR CDMEIF2 LL_DMA_ClearFlag_DME2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF2); -} - -/** - * @brief Clear Stream 3 direct mode error flag. - * @rmtoll LIFCR CDMEIF3 LL_DMA_ClearFlag_DME3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF3); -} - -/** - * @brief Clear Stream 4 direct mode error flag. - * @rmtoll HIFCR CDMEIF4 LL_DMA_ClearFlag_DME4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF4); -} - -/** - * @brief Clear Stream 5 direct mode error flag. - * @rmtoll HIFCR CDMEIF5 LL_DMA_ClearFlag_DME5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF5); -} - -/** - * @brief Clear Stream 6 direct mode error flag. - * @rmtoll HIFCR CDMEIF6 LL_DMA_ClearFlag_DME6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF6); -} - -/** - * @brief Clear Stream 7 direct mode error flag. - * @rmtoll HIFCR CDMEIF7 LL_DMA_ClearFlag_DME7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF7); -} - -/** - * @brief Clear Stream 0 FIFO error flag. - * @rmtoll LIFCR CFEIF0 LL_DMA_ClearFlag_FE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF0); -} - -/** - * @brief Clear Stream 1 FIFO error flag. - * @rmtoll LIFCR CFEIF1 LL_DMA_ClearFlag_FE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF1); -} - -/** - * @brief Clear Stream 2 FIFO error flag. - * @rmtoll LIFCR CFEIF2 LL_DMA_ClearFlag_FE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF2); -} - -/** - * @brief Clear Stream 3 FIFO error flag. - * @rmtoll LIFCR CFEIF3 LL_DMA_ClearFlag_FE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF3); -} - -/** - * @brief Clear Stream 4 FIFO error flag. - * @rmtoll HIFCR CFEIF4 LL_DMA_ClearFlag_FE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF4); -} - -/** - * @brief Clear Stream 5 FIFO error flag. - * @rmtoll HIFCR CFEIF5 LL_DMA_ClearFlag_FE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF5); -} - -/** - * @brief Clear Stream 6 FIFO error flag. - * @rmtoll HIFCR CFEIF6 LL_DMA_ClearFlag_FE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF6); -} - -/** - * @brief Clear Stream 7 FIFO error flag. - * @rmtoll HIFCR CFEIF7 LL_DMA_ClearFlag_FE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF7); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_EnableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Enable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_EnableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Enable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_EnableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Enable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_EnableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Enable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_EnableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Disable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_DisableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Disable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_DisableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Disable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_DisableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Disable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_DisableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Disable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_DisableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Check if Half transfer interrupt is enabled. - * @rmtoll CR HTIE LL_DMA_IsEnabledIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE) == DMA_SxCR_HTIE); -} - -/** - * @brief Check if Transfer error nterrup is enabled. - * @rmtoll CR TEIE LL_DMA_IsEnabledIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE) == DMA_SxCR_TEIE); -} - -/** - * @brief Check if Transfer complete interrupt is enabled. - * @rmtoll CR TCIE LL_DMA_IsEnabledIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE) == DMA_SxCR_TCIE); -} - -/** - * @brief Check if Direct mode error interrupt is enabled. - * @rmtoll CR DMEIE LL_DMA_IsEnabledIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE) == DMA_SxCR_DMEIE); -} - -/** - * @brief Check if FIFO error interrupt is enabled. - * @rmtoll FCR FEIE LL_DMA_IsEnabledIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE) == DMA_SxFCR_FEIE); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct); -uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream); -void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DMA1 || DMA2 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_DMA_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_dma.h + * @author MCD Application Team + * @brief Header file of DMA LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_DMA_H +#define __STM32F4xx_LL_DMA_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (DMA1) || defined (DMA2) + +/** @defgroup DMA_LL DMA + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup DMA_LL_Private_Variables DMA Private Variables + * @{ + */ +/* Array used to get the DMA stream register offset versus stream index LL_DMA_STREAM_x */ +static const uint8_t STREAM_OFFSET_TAB[] = +{ + (uint8_t)(DMA1_Stream0_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream1_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream2_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream3_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream4_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream5_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream6_BASE - DMA1_BASE), + (uint8_t)(DMA1_Stream7_BASE - DMA1_BASE) +}; + +/** + * @} + */ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup DMA_LL_Private_Constants DMA Private Constants + * @{ + */ +/** + * @} + */ + + +/* Private macros ------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup DMA_LL_ES_INIT DMA Exported Init structure + * @{ + */ +typedef struct +{ + uint32_t PeriphOrM2MSrcAddress; /*!< Specifies the peripheral base address for DMA transfer + or as Source base address in case of memory to memory transfer direction. + + This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ + + uint32_t MemoryOrM2MDstAddress; /*!< Specifies the memory base address for DMA transfer + or as Destination base address in case of memory to memory transfer direction. + + This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ + + uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, + from memory to memory or from peripheral to memory. + This parameter can be a value of @ref DMA_LL_EC_DIRECTION + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataTransferDirection(). */ + + uint32_t Mode; /*!< Specifies the normal or circular operation mode. + This parameter can be a value of @ref DMA_LL_EC_MODE + @note The circular buffer mode cannot be used if the memory to memory + data transfer direction is configured on the selected Stream + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetMode(). */ + + uint32_t PeriphOrM2MSrcIncMode; /*!< Specifies whether the Peripheral address or Source address in case of memory to memory transfer direction + is incremented or not. + This parameter can be a value of @ref DMA_LL_EC_PERIPH + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphIncMode(). */ + + uint32_t MemoryOrM2MDstIncMode; /*!< Specifies whether the Memory address or Destination address in case of memory to memory transfer direction + is incremented or not. + This parameter can be a value of @ref DMA_LL_EC_MEMORY + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryIncMode(). */ + + uint32_t PeriphOrM2MSrcDataSize; /*!< Specifies the Peripheral data size alignment or Source data size alignment (byte, half word, word) + in case of memory to memory transfer direction. + This parameter can be a value of @ref DMA_LL_EC_PDATAALIGN + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphSize(). */ + + uint32_t MemoryOrM2MDstDataSize; /*!< Specifies the Memory data size alignment or Destination data size alignment (byte, half word, word) + in case of memory to memory transfer direction. + This parameter can be a value of @ref DMA_LL_EC_MDATAALIGN + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemorySize(). */ + + uint32_t NbData; /*!< Specifies the number of data to transfer, in data unit. + The data unit is equal to the source buffer configuration set in PeripheralSize + or MemorySize parameters depending in the transfer direction. + This parameter must be a value between Min_Data = 0 and Max_Data = 0x0000FFFF + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataLength(). */ + + uint32_t Channel; /*!< Specifies the peripheral channel. + This parameter can be a value of @ref DMA_LL_EC_CHANNEL + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetChannelSelection(). */ + + uint32_t Priority; /*!< Specifies the channel priority level. + This parameter can be a value of @ref DMA_LL_EC_PRIORITY + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetStreamPriorityLevel(). */ + + uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. + This parameter can be a value of @ref DMA_LL_FIFOMODE + @note The Direct mode (FIFO mode disabled) cannot be used if the + memory-to-memory data transfer is configured on the selected stream + + This feature can be modified afterwards using unitary functions @ref LL_DMA_EnableFifoMode() or @ref LL_DMA_EnableFifoMode() . */ + + uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. + This parameter can be a value of @ref DMA_LL_EC_FIFOTHRESHOLD + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetFIFOThreshold(). */ + + uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. + It specifies the amount of data to be transferred in a single non interruptible + transaction. + This parameter can be a value of @ref DMA_LL_EC_MBURST + @note The burst mode is possible only if the address Increment mode is enabled. + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryBurstxfer(). */ + + uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. + It specifies the amount of data to be transferred in a single non interruptible + transaction. + This parameter can be a value of @ref DMA_LL_EC_PBURST + @note The burst mode is possible only if the address Increment mode is enabled. + + This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphBurstxfer(). */ + +} LL_DMA_InitTypeDef; +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup DMA_LL_Exported_Constants DMA Exported Constants + * @{ + */ + +/** @defgroup DMA_LL_EC_STREAM STREAM + * @{ + */ +#define LL_DMA_STREAM_0 0x00000000U +#define LL_DMA_STREAM_1 0x00000001U +#define LL_DMA_STREAM_2 0x00000002U +#define LL_DMA_STREAM_3 0x00000003U +#define LL_DMA_STREAM_4 0x00000004U +#define LL_DMA_STREAM_5 0x00000005U +#define LL_DMA_STREAM_6 0x00000006U +#define LL_DMA_STREAM_7 0x00000007U +#define LL_DMA_STREAM_ALL 0xFFFF0000U +/** + * @} + */ + +/** @defgroup DMA_LL_EC_DIRECTION DIRECTION + * @{ + */ +#define LL_DMA_DIRECTION_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ +#define LL_DMA_DIRECTION_MEMORY_TO_PERIPH DMA_SxCR_DIR_0 /*!< Memory to peripheral direction */ +#define LL_DMA_DIRECTION_MEMORY_TO_MEMORY DMA_SxCR_DIR_1 /*!< Memory to memory direction */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_MODE MODE + * @{ + */ +#define LL_DMA_MODE_NORMAL 0x00000000U /*!< Normal Mode */ +#define LL_DMA_MODE_CIRCULAR DMA_SxCR_CIRC /*!< Circular Mode */ +#define LL_DMA_MODE_PFCTRL DMA_SxCR_PFCTRL /*!< Peripheral flow control mode */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_DOUBLEBUFFER_MODE DOUBLEBUFFER MODE + * @{ + */ +#define LL_DMA_DOUBLEBUFFER_MODE_DISABLE 0x00000000U /*!< Disable double buffering mode */ +#define LL_DMA_DOUBLEBUFFER_MODE_ENABLE DMA_SxCR_DBM /*!< Enable double buffering mode */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_PERIPH PERIPH + * @{ + */ +#define LL_DMA_PERIPH_NOINCREMENT 0x00000000U /*!< Peripheral increment mode Disable */ +#define LL_DMA_PERIPH_INCREMENT DMA_SxCR_PINC /*!< Peripheral increment mode Enable */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_MEMORY MEMORY + * @{ + */ +#define LL_DMA_MEMORY_NOINCREMENT 0x00000000U /*!< Memory increment mode Disable */ +#define LL_DMA_MEMORY_INCREMENT DMA_SxCR_MINC /*!< Memory increment mode Enable */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_PDATAALIGN PDATAALIGN + * @{ + */ +#define LL_DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment : Byte */ +#define LL_DMA_PDATAALIGN_HALFWORD DMA_SxCR_PSIZE_0 /*!< Peripheral data alignment : HalfWord */ +#define LL_DMA_PDATAALIGN_WORD DMA_SxCR_PSIZE_1 /*!< Peripheral data alignment : Word */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_MDATAALIGN MDATAALIGN + * @{ + */ +#define LL_DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment : Byte */ +#define LL_DMA_MDATAALIGN_HALFWORD DMA_SxCR_MSIZE_0 /*!< Memory data alignment : HalfWord */ +#define LL_DMA_MDATAALIGN_WORD DMA_SxCR_MSIZE_1 /*!< Memory data alignment : Word */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_OFFSETSIZE OFFSETSIZE + * @{ + */ +#define LL_DMA_OFFSETSIZE_PSIZE 0x00000000U /*!< Peripheral increment offset size is linked to the PSIZE */ +#define LL_DMA_OFFSETSIZE_FIXEDTO4 DMA_SxCR_PINCOS /*!< Peripheral increment offset size is fixed to 4 (32-bit alignment) */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_PRIORITY PRIORITY + * @{ + */ +#define LL_DMA_PRIORITY_LOW 0x00000000U /*!< Priority level : Low */ +#define LL_DMA_PRIORITY_MEDIUM DMA_SxCR_PL_0 /*!< Priority level : Medium */ +#define LL_DMA_PRIORITY_HIGH DMA_SxCR_PL_1 /*!< Priority level : High */ +#define LL_DMA_PRIORITY_VERYHIGH DMA_SxCR_PL /*!< Priority level : Very_High */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_CHANNEL CHANNEL + * @{ + */ +#define LL_DMA_CHANNEL_0 0x00000000U /* Select Channel0 of DMA Instance */ +#define LL_DMA_CHANNEL_1 DMA_SxCR_CHSEL_0 /* Select Channel1 of DMA Instance */ +#define LL_DMA_CHANNEL_2 DMA_SxCR_CHSEL_1 /* Select Channel2 of DMA Instance */ +#define LL_DMA_CHANNEL_3 (DMA_SxCR_CHSEL_0 | DMA_SxCR_CHSEL_1) /* Select Channel3 of DMA Instance */ +#define LL_DMA_CHANNEL_4 DMA_SxCR_CHSEL_2 /* Select Channel4 of DMA Instance */ +#define LL_DMA_CHANNEL_5 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel5 of DMA Instance */ +#define LL_DMA_CHANNEL_6 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel6 of DMA Instance */ +#define LL_DMA_CHANNEL_7 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel7 of DMA Instance */ +#if defined (DMA_SxCR_CHSEL_3) +#define LL_DMA_CHANNEL_8 DMA_SxCR_CHSEL_3 /* Select Channel8 of DMA Instance */ +#define LL_DMA_CHANNEL_9 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_0) /* Select Channel9 of DMA Instance */ +#define LL_DMA_CHANNEL_10 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1) /* Select Channel10 of DMA Instance */ +#define LL_DMA_CHANNEL_11 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel11 of DMA Instance */ +#define LL_DMA_CHANNEL_12 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2) /* Select Channel12 of DMA Instance */ +#define LL_DMA_CHANNEL_13 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel13 of DMA Instance */ +#define LL_DMA_CHANNEL_14 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel14 of DMA Instance */ +#define LL_DMA_CHANNEL_15 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel15 of DMA Instance */ +#endif /* DMA_SxCR_CHSEL_3 */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_MBURST MBURST + * @{ + */ +#define LL_DMA_MBURST_SINGLE 0x00000000U /*!< Memory burst single transfer configuration */ +#define LL_DMA_MBURST_INC4 DMA_SxCR_MBURST_0 /*!< Memory burst of 4 beats transfer configuration */ +#define LL_DMA_MBURST_INC8 DMA_SxCR_MBURST_1 /*!< Memory burst of 8 beats transfer configuration */ +#define LL_DMA_MBURST_INC16 (DMA_SxCR_MBURST_0 | DMA_SxCR_MBURST_1) /*!< Memory burst of 16 beats transfer configuration */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_PBURST PBURST + * @{ + */ +#define LL_DMA_PBURST_SINGLE 0x00000000U /*!< Peripheral burst single transfer configuration */ +#define LL_DMA_PBURST_INC4 DMA_SxCR_PBURST_0 /*!< Peripheral burst of 4 beats transfer configuration */ +#define LL_DMA_PBURST_INC8 DMA_SxCR_PBURST_1 /*!< Peripheral burst of 8 beats transfer configuration */ +#define LL_DMA_PBURST_INC16 (DMA_SxCR_PBURST_0 | DMA_SxCR_PBURST_1) /*!< Peripheral burst of 16 beats transfer configuration */ +/** + * @} + */ + +/** @defgroup DMA_LL_FIFOMODE DMA_LL_FIFOMODE + * @{ + */ +#define LL_DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable (direct mode is enabled) */ +#define LL_DMA_FIFOMODE_ENABLE DMA_SxFCR_DMDIS /*!< FIFO mode enable */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_FIFOSTATUS_0 FIFOSTATUS 0 + * @{ + */ +#define LL_DMA_FIFOSTATUS_0_25 0x00000000U /*!< 0 < fifo_level < 1/4 */ +#define LL_DMA_FIFOSTATUS_25_50 DMA_SxFCR_FS_0 /*!< 1/4 < fifo_level < 1/2 */ +#define LL_DMA_FIFOSTATUS_50_75 DMA_SxFCR_FS_1 /*!< 1/2 < fifo_level < 3/4 */ +#define LL_DMA_FIFOSTATUS_75_100 (DMA_SxFCR_FS_1 | DMA_SxFCR_FS_0) /*!< 3/4 < fifo_level < full */ +#define LL_DMA_FIFOSTATUS_EMPTY DMA_SxFCR_FS_2 /*!< FIFO is empty */ +#define LL_DMA_FIFOSTATUS_FULL (DMA_SxFCR_FS_2 | DMA_SxFCR_FS_0) /*!< FIFO is full */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_FIFOTHRESHOLD FIFOTHRESHOLD + * @{ + */ +#define LL_DMA_FIFOTHRESHOLD_1_4 0x00000000U /*!< FIFO threshold 1 quart full configuration */ +#define LL_DMA_FIFOTHRESHOLD_1_2 DMA_SxFCR_FTH_0 /*!< FIFO threshold half full configuration */ +#define LL_DMA_FIFOTHRESHOLD_3_4 DMA_SxFCR_FTH_1 /*!< FIFO threshold 3 quarts full configuration */ +#define LL_DMA_FIFOTHRESHOLD_FULL DMA_SxFCR_FTH /*!< FIFO threshold full configuration */ +/** + * @} + */ + +/** @defgroup DMA_LL_EC_CURRENTTARGETMEM CURRENTTARGETMEM + * @{ + */ +#define LL_DMA_CURRENTTARGETMEM0 0x00000000U /*!< Set CurrentTarget Memory to Memory 0 */ +#define LL_DMA_CURRENTTARGETMEM1 DMA_SxCR_CT /*!< Set CurrentTarget Memory to Memory 1 */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup DMA_LL_Exported_Macros DMA Exported Macros + * @{ + */ + +/** @defgroup DMA_LL_EM_WRITE_READ Common Write and read registers macros + * @{ + */ +/** + * @brief Write a value in DMA register + * @param __INSTANCE__ DMA Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_DMA_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in DMA register + * @param __INSTANCE__ DMA Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_DMA_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** @defgroup DMA_LL_EM_CONVERT_DMAxCHANNELy Convert DMAxStreamy + * @{ + */ +/** + * @brief Convert DMAx_Streamy into DMAx + * @param __STREAM_INSTANCE__ DMAx_Streamy + * @retval DMAx + */ +#define __LL_DMA_GET_INSTANCE(__STREAM_INSTANCE__) \ +(((uint32_t)(__STREAM_INSTANCE__) > ((uint32_t)DMA1_Stream7)) ? DMA2 : DMA1) + +/** + * @brief Convert DMAx_Streamy into LL_DMA_STREAM_y + * @param __STREAM_INSTANCE__ DMAx_Streamy + * @retval LL_DMA_CHANNEL_y + */ +#define __LL_DMA_GET_STREAM(__STREAM_INSTANCE__) \ +(((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream0)) ? LL_DMA_STREAM_0 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream0)) ? LL_DMA_STREAM_0 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream1)) ? LL_DMA_STREAM_1 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream1)) ? LL_DMA_STREAM_1 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream2)) ? LL_DMA_STREAM_2 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream2)) ? LL_DMA_STREAM_2 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream3)) ? LL_DMA_STREAM_3 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream3)) ? LL_DMA_STREAM_3 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream4)) ? LL_DMA_STREAM_4 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream4)) ? LL_DMA_STREAM_4 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream5)) ? LL_DMA_STREAM_5 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream5)) ? LL_DMA_STREAM_5 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream6)) ? LL_DMA_STREAM_6 : \ + ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream6)) ? LL_DMA_STREAM_6 : \ + LL_DMA_STREAM_7) + +/** + * @brief Convert DMA Instance DMAx and LL_DMA_STREAM_y into DMAx_Streamy + * @param __DMA_INSTANCE__ DMAx + * @param __STREAM__ LL_DMA_STREAM_y + * @retval DMAx_Streamy + */ +#define __LL_DMA_GET_STREAM_INSTANCE(__DMA_INSTANCE__, __STREAM__) \ +((((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA1_Stream0 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA2_Stream0 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA1_Stream1 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA2_Stream1 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA1_Stream2 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA2_Stream2 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA1_Stream3 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA2_Stream3 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA1_Stream4 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA2_Stream4 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA1_Stream5 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA2_Stream5 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA1_Stream6 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA2_Stream6 : \ + (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_7))) ? DMA1_Stream7 : \ + DMA2_Stream7) + +/** + * @} + */ + +/** + * @} + */ + + +/* Exported functions --------------------------------------------------------*/ + /** @defgroup DMA_LL_Exported_Functions DMA Exported Functions + * @{ + */ + +/** @defgroup DMA_LL_EF_Configuration Configuration + * @{ + */ +/** + * @brief Enable DMA stream. + * @rmtoll CR EN LL_DMA_EnableStream + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableStream(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); +} + +/** + * @brief Disable DMA stream. + * @rmtoll CR EN LL_DMA_DisableStream + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableStream(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); +} + +/** + * @brief Check if DMA stream is enabled or disabled. + * @rmtoll CR EN LL_DMA_IsEnabledStream + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledStream(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN) == (DMA_SxCR_EN)); +} + +/** + * @brief Configure all parameters linked to DMA transfer. + * @rmtoll CR DIR LL_DMA_ConfigTransfer\n + * CR CIRC LL_DMA_ConfigTransfer\n + * CR PINC LL_DMA_ConfigTransfer\n + * CR MINC LL_DMA_ConfigTransfer\n + * CR PSIZE LL_DMA_ConfigTransfer\n + * CR MSIZE LL_DMA_ConfigTransfer\n + * CR PL LL_DMA_ConfigTransfer\n + * CR PFCTRL LL_DMA_ConfigTransfer + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Configuration This parameter must be a combination of all the following values: + * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY or @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH or @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY + * @arg @ref LL_DMA_MODE_NORMAL or @ref LL_DMA_MODE_CIRCULAR or @ref LL_DMA_MODE_PFCTRL + * @arg @ref LL_DMA_PERIPH_INCREMENT or @ref LL_DMA_PERIPH_NOINCREMENT + * @arg @ref LL_DMA_MEMORY_INCREMENT or @ref LL_DMA_MEMORY_NOINCREMENT + * @arg @ref LL_DMA_PDATAALIGN_BYTE or @ref LL_DMA_PDATAALIGN_HALFWORD or @ref LL_DMA_PDATAALIGN_WORD + * @arg @ref LL_DMA_MDATAALIGN_BYTE or @ref LL_DMA_MDATAALIGN_HALFWORD or @ref LL_DMA_MDATAALIGN_WORD + * @arg @ref LL_DMA_PRIORITY_LOW or @ref LL_DMA_PRIORITY_MEDIUM or @ref LL_DMA_PRIORITY_HIGH or @ref LL_DMA_PRIORITY_VERYHIGH + *@retval None + */ +__STATIC_INLINE void LL_DMA_ConfigTransfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Configuration) +{ + MODIFY_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, + DMA_SxCR_DIR | DMA_SxCR_CIRC | DMA_SxCR_PINC | DMA_SxCR_MINC | DMA_SxCR_PSIZE | DMA_SxCR_MSIZE | DMA_SxCR_PL | DMA_SxCR_PFCTRL, + Configuration); +} + +/** + * @brief Set Data transfer direction (read from peripheral or from memory). + * @rmtoll CR DIR LL_DMA_SetDataTransferDirection + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Direction This parameter can be one of the following values: + * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Direction) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR, Direction); +} + +/** + * @brief Get Data transfer direction (read from peripheral or from memory). + * @rmtoll CR DIR LL_DMA_GetDataTransferDirection + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY + */ +__STATIC_INLINE uint32_t LL_DMA_GetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR)); +} + +/** + * @brief Set DMA mode normal, circular or peripheral flow control. + * @rmtoll CR CIRC LL_DMA_SetMode\n + * CR PFCTRL LL_DMA_SetMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Mode This parameter can be one of the following values: + * @arg @ref LL_DMA_MODE_NORMAL + * @arg @ref LL_DMA_MODE_CIRCULAR + * @arg @ref LL_DMA_MODE_PFCTRL + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mode) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL, Mode); +} + +/** + * @brief Get DMA mode normal, circular or peripheral flow control. + * @rmtoll CR CIRC LL_DMA_GetMode\n + * CR PFCTRL LL_DMA_GetMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_MODE_NORMAL + * @arg @ref LL_DMA_MODE_CIRCULAR + * @arg @ref LL_DMA_MODE_PFCTRL + */ +__STATIC_INLINE uint32_t LL_DMA_GetMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL)); +} + +/** + * @brief Set Peripheral increment mode. + * @rmtoll CR PINC LL_DMA_SetPeriphIncMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param IncrementMode This parameter can be one of the following values: + * @arg @ref LL_DMA_PERIPH_NOINCREMENT + * @arg @ref LL_DMA_PERIPH_INCREMENT + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC, IncrementMode); +} + +/** + * @brief Get Peripheral increment mode. + * @rmtoll CR PINC LL_DMA_GetPeriphIncMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_PERIPH_NOINCREMENT + * @arg @ref LL_DMA_PERIPH_INCREMENT + */ +__STATIC_INLINE uint32_t LL_DMA_GetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC)); +} + +/** + * @brief Set Memory increment mode. + * @rmtoll CR MINC LL_DMA_SetMemoryIncMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param IncrementMode This parameter can be one of the following values: + * @arg @ref LL_DMA_MEMORY_NOINCREMENT + * @arg @ref LL_DMA_MEMORY_INCREMENT + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC, IncrementMode); +} + +/** + * @brief Get Memory increment mode. + * @rmtoll CR MINC LL_DMA_GetMemoryIncMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_MEMORY_NOINCREMENT + * @arg @ref LL_DMA_MEMORY_INCREMENT + */ +__STATIC_INLINE uint32_t LL_DMA_GetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC)); +} + +/** + * @brief Set Peripheral size. + * @rmtoll CR PSIZE LL_DMA_SetPeriphSize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Size This parameter can be one of the following values: + * @arg @ref LL_DMA_PDATAALIGN_BYTE + * @arg @ref LL_DMA_PDATAALIGN_HALFWORD + * @arg @ref LL_DMA_PDATAALIGN_WORD + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE, Size); +} + +/** + * @brief Get Peripheral size. + * @rmtoll CR PSIZE LL_DMA_GetPeriphSize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_PDATAALIGN_BYTE + * @arg @ref LL_DMA_PDATAALIGN_HALFWORD + * @arg @ref LL_DMA_PDATAALIGN_WORD + */ +__STATIC_INLINE uint32_t LL_DMA_GetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE)); +} + +/** + * @brief Set Memory size. + * @rmtoll CR MSIZE LL_DMA_SetMemorySize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Size This parameter can be one of the following values: + * @arg @ref LL_DMA_MDATAALIGN_BYTE + * @arg @ref LL_DMA_MDATAALIGN_HALFWORD + * @arg @ref LL_DMA_MDATAALIGN_WORD + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE, Size); +} + +/** + * @brief Get Memory size. + * @rmtoll CR MSIZE LL_DMA_GetMemorySize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_MDATAALIGN_BYTE + * @arg @ref LL_DMA_MDATAALIGN_HALFWORD + * @arg @ref LL_DMA_MDATAALIGN_WORD + */ +__STATIC_INLINE uint32_t LL_DMA_GetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE)); +} + +/** + * @brief Set Peripheral increment offset size. + * @rmtoll CR PINCOS LL_DMA_SetIncOffsetSize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param OffsetSize This parameter can be one of the following values: + * @arg @ref LL_DMA_OFFSETSIZE_PSIZE + * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t OffsetSize) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS, OffsetSize); +} + +/** + * @brief Get Peripheral increment offset size. + * @rmtoll CR PINCOS LL_DMA_GetIncOffsetSize + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_OFFSETSIZE_PSIZE + * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 + */ +__STATIC_INLINE uint32_t LL_DMA_GetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS)); +} + +/** + * @brief Set Stream priority level. + * @rmtoll CR PL LL_DMA_SetStreamPriorityLevel + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Priority This parameter can be one of the following values: + * @arg @ref LL_DMA_PRIORITY_LOW + * @arg @ref LL_DMA_PRIORITY_MEDIUM + * @arg @ref LL_DMA_PRIORITY_HIGH + * @arg @ref LL_DMA_PRIORITY_VERYHIGH + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Priority) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL, Priority); +} + +/** + * @brief Get Stream priority level. + * @rmtoll CR PL LL_DMA_GetStreamPriorityLevel + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_PRIORITY_LOW + * @arg @ref LL_DMA_PRIORITY_MEDIUM + * @arg @ref LL_DMA_PRIORITY_HIGH + * @arg @ref LL_DMA_PRIORITY_VERYHIGH + */ +__STATIC_INLINE uint32_t LL_DMA_GetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL)); +} + +/** + * @brief Set Number of data to transfer. + * @rmtoll NDTR NDT LL_DMA_SetDataLength + * @note This action has no effect if + * stream is enabled. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param NbData Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetDataLength(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t NbData) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT, NbData); +} + +/** + * @brief Get Number of data to transfer. + * @rmtoll NDTR NDT LL_DMA_GetDataLength + * @note Once the stream is enabled, the return value indicate the + * remaining bytes to be transmitted. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetDataLength(DMA_TypeDef* DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT)); +} + +/** + * @brief Select Channel number associated to the Stream. + * @rmtoll CR CHSEL LL_DMA_SetChannelSelection + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_DMA_CHANNEL_0 + * @arg @ref LL_DMA_CHANNEL_1 + * @arg @ref LL_DMA_CHANNEL_2 + * @arg @ref LL_DMA_CHANNEL_3 + * @arg @ref LL_DMA_CHANNEL_4 + * @arg @ref LL_DMA_CHANNEL_5 + * @arg @ref LL_DMA_CHANNEL_6 + * @arg @ref LL_DMA_CHANNEL_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Channel) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL, Channel); +} + +/** + * @brief Get the Channel number associated to the Stream. + * @rmtoll CR CHSEL LL_DMA_GetChannelSelection + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_CHANNEL_0 + * @arg @ref LL_DMA_CHANNEL_1 + * @arg @ref LL_DMA_CHANNEL_2 + * @arg @ref LL_DMA_CHANNEL_3 + * @arg @ref LL_DMA_CHANNEL_4 + * @arg @ref LL_DMA_CHANNEL_5 + * @arg @ref LL_DMA_CHANNEL_6 + * @arg @ref LL_DMA_CHANNEL_7 + */ +__STATIC_INLINE uint32_t LL_DMA_GetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL)); +} + +/** + * @brief Set Memory burst transfer configuration. + * @rmtoll CR MBURST LL_DMA_SetMemoryBurstxfer + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Mburst This parameter can be one of the following values: + * @arg @ref LL_DMA_MBURST_SINGLE + * @arg @ref LL_DMA_MBURST_INC4 + * @arg @ref LL_DMA_MBURST_INC8 + * @arg @ref LL_DMA_MBURST_INC16 + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mburst) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST, Mburst); +} + +/** + * @brief Get Memory burst transfer configuration. + * @rmtoll CR MBURST LL_DMA_GetMemoryBurstxfer + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_MBURST_SINGLE + * @arg @ref LL_DMA_MBURST_INC4 + * @arg @ref LL_DMA_MBURST_INC8 + * @arg @ref LL_DMA_MBURST_INC16 + */ +__STATIC_INLINE uint32_t LL_DMA_GetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST)); +} + +/** + * @brief Set Peripheral burst transfer configuration. + * @rmtoll CR PBURST LL_DMA_SetPeriphBurstxfer + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Pburst This parameter can be one of the following values: + * @arg @ref LL_DMA_PBURST_SINGLE + * @arg @ref LL_DMA_PBURST_INC4 + * @arg @ref LL_DMA_PBURST_INC8 + * @arg @ref LL_DMA_PBURST_INC16 + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Pburst) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST, Pburst); +} + +/** + * @brief Get Peripheral burst transfer configuration. + * @rmtoll CR PBURST LL_DMA_GetPeriphBurstxfer + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_PBURST_SINGLE + * @arg @ref LL_DMA_PBURST_INC4 + * @arg @ref LL_DMA_PBURST_INC8 + * @arg @ref LL_DMA_PBURST_INC16 + */ +__STATIC_INLINE uint32_t LL_DMA_GetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST)); +} + +/** + * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. + * @rmtoll CR CT LL_DMA_SetCurrentTargetMem + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param CurrentMemory This parameter can be one of the following values: + * @arg @ref LL_DMA_CURRENTTARGETMEM0 + * @arg @ref LL_DMA_CURRENTTARGETMEM1 + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t CurrentMemory) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT, CurrentMemory); +} + +/** + * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. + * @rmtoll CR CT LL_DMA_GetCurrentTargetMem + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_CURRENTTARGETMEM0 + * @arg @ref LL_DMA_CURRENTTARGETMEM1 + */ +__STATIC_INLINE uint32_t LL_DMA_GetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT)); +} + +/** + * @brief Enable the double buffer mode. + * @rmtoll CR DBM LL_DMA_EnableDoubleBufferMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); +} + +/** + * @brief Disable the double buffer mode. + * @rmtoll CR DBM LL_DMA_DisableDoubleBufferMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); +} + +/** + * @brief Get FIFO status. + * @rmtoll FCR FS LL_DMA_GetFIFOStatus + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_FIFOSTATUS_0_25 + * @arg @ref LL_DMA_FIFOSTATUS_25_50 + * @arg @ref LL_DMA_FIFOSTATUS_50_75 + * @arg @ref LL_DMA_FIFOSTATUS_75_100 + * @arg @ref LL_DMA_FIFOSTATUS_EMPTY + * @arg @ref LL_DMA_FIFOSTATUS_FULL + */ +__STATIC_INLINE uint32_t LL_DMA_GetFIFOStatus(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FS)); +} + +/** + * @brief Disable Fifo mode. + * @rmtoll FCR DMDIS LL_DMA_DisableFifoMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); +} + +/** + * @brief Enable Fifo mode. + * @rmtoll FCR DMDIS LL_DMA_EnableFifoMode + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); +} + +/** + * @brief Select FIFO threshold. + * @rmtoll FCR FTH LL_DMA_SetFIFOThreshold + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Threshold This parameter can be one of the following values: + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 + * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Threshold) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH, Threshold); +} + +/** + * @brief Get FIFO threshold. + * @rmtoll FCR FTH LL_DMA_GetFIFOThreshold + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 + * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL + */ +__STATIC_INLINE uint32_t LL_DMA_GetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH)); +} + +/** + * @brief Configure the FIFO . + * @rmtoll FCR FTH LL_DMA_ConfigFifo\n + * FCR DMDIS LL_DMA_ConfigFifo + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param FifoMode This parameter can be one of the following values: + * @arg @ref LL_DMA_FIFOMODE_ENABLE + * @arg @ref LL_DMA_FIFOMODE_DISABLE + * @param FifoThreshold This parameter can be one of the following values: + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 + * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 + * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL + * @retval None + */ +__STATIC_INLINE void LL_DMA_ConfigFifo(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t FifoMode, uint32_t FifoThreshold) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH|DMA_SxFCR_DMDIS, FifoMode|FifoThreshold); +} + +/** + * @brief Configure the Source and Destination addresses. + * @note This API must not be called when the DMA stream is enabled. + * @rmtoll M0AR M0A LL_DMA_ConfigAddresses\n + * PAR PA LL_DMA_ConfigAddresses + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param SrcAddress Between 0 to 0xFFFFFFFF + * @param DstAddress Between 0 to 0xFFFFFFFF + * @param Direction This parameter can be one of the following values: + * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH + * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY + * @retval None + */ +__STATIC_INLINE void LL_DMA_ConfigAddresses(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t SrcAddress, uint32_t DstAddress, uint32_t Direction) +{ + /* Direction Memory to Periph */ + if (Direction == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) + { + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, SrcAddress); + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, DstAddress); + } + /* Direction Periph to Memory and Memory to Memory */ + else + { + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, SrcAddress); + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, DstAddress); + } +} + +/** + * @brief Set the Memory address. + * @rmtoll M0AR M0A LL_DMA_SetMemoryAddress + * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. + * @note This API must not be called when the DMA channel is enabled. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param MemoryAddress Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) +{ + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); +} + +/** + * @brief Set the Peripheral address. + * @rmtoll PAR PA LL_DMA_SetPeriphAddress + * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. + * @note This API must not be called when the DMA channel is enabled. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param PeriphAddress Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t PeriphAddress) +{ + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, PeriphAddress); +} + +/** + * @brief Get the Memory address. + * @rmtoll M0AR M0A LL_DMA_GetMemoryAddress + * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream) +{ + return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); +} + +/** + * @brief Get the Peripheral address. + * @rmtoll PAR PA LL_DMA_GetPeriphAddress + * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream) +{ + return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); +} + +/** + * @brief Set the Memory to Memory Source address. + * @rmtoll PAR PA LL_DMA_SetM2MSrcAddress + * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. + * @note This API must not be called when the DMA channel is enabled. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param MemoryAddress Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) +{ + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, MemoryAddress); +} + +/** + * @brief Set the Memory to Memory Destination address. + * @rmtoll M0AR M0A LL_DMA_SetM2MDstAddress + * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. + * @note This API must not be called when the DMA channel is enabled. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param MemoryAddress Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) + { + WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); + } + +/** + * @brief Get the Memory to Memory Source address. + * @rmtoll PAR PA LL_DMA_GetM2MSrcAddress + * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream) + { + return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); + } + +/** + * @brief Get the Memory to Memory Destination address. + * @rmtoll M0AR M0A LL_DMA_GetM2MDstAddress + * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream) +{ + return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); +} + +/** + * @brief Set Memory 1 address (used in case of Double buffer mode). + * @rmtoll M1AR M1A LL_DMA_SetMemory1Address + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param Address Between 0 to 0xFFFFFFFF + * @retval None + */ +__STATIC_INLINE void LL_DMA_SetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Address) +{ + MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR, DMA_SxM1AR_M1A, Address); +} + +/** + * @brief Get Memory 1 address (used in case of Double buffer mode). + * @rmtoll M1AR M1A LL_DMA_GetMemory1Address + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval Between 0 to 0xFFFFFFFF + */ +__STATIC_INLINE uint32_t LL_DMA_GetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR); +} + +/** + * @} + */ + +/** @defgroup DMA_LL_EF_FLAG_Management FLAG_Management + * @{ + */ + +/** + * @brief Get Stream 0 half transfer flag. + * @rmtoll LISR HTIF0 LL_DMA_IsActiveFlag_HT0 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT0(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF0)==(DMA_LISR_HTIF0)); +} + +/** + * @brief Get Stream 1 half transfer flag. + * @rmtoll LISR HTIF1 LL_DMA_IsActiveFlag_HT1 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT1(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF1)==(DMA_LISR_HTIF1)); +} + +/** + * @brief Get Stream 2 half transfer flag. + * @rmtoll LISR HTIF2 LL_DMA_IsActiveFlag_HT2 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT2(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF2)==(DMA_LISR_HTIF2)); +} + +/** + * @brief Get Stream 3 half transfer flag. + * @rmtoll LISR HTIF3 LL_DMA_IsActiveFlag_HT3 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT3(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF3)==(DMA_LISR_HTIF3)); +} + +/** + * @brief Get Stream 4 half transfer flag. + * @rmtoll HISR HTIF4 LL_DMA_IsActiveFlag_HT4 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT4(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF4)==(DMA_HISR_HTIF4)); +} + +/** + * @brief Get Stream 5 half transfer flag. + * @rmtoll HISR HTIF0 LL_DMA_IsActiveFlag_HT5 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT5(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF5)==(DMA_HISR_HTIF5)); +} + +/** + * @brief Get Stream 6 half transfer flag. + * @rmtoll HISR HTIF6 LL_DMA_IsActiveFlag_HT6 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT6(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF6)==(DMA_HISR_HTIF6)); +} + +/** + * @brief Get Stream 7 half transfer flag. + * @rmtoll HISR HTIF7 LL_DMA_IsActiveFlag_HT7 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT7(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF7)==(DMA_HISR_HTIF7)); +} + +/** + * @brief Get Stream 0 transfer complete flag. + * @rmtoll LISR TCIF0 LL_DMA_IsActiveFlag_TC0 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC0(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF0)==(DMA_LISR_TCIF0)); +} + +/** + * @brief Get Stream 1 transfer complete flag. + * @rmtoll LISR TCIF1 LL_DMA_IsActiveFlag_TC1 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC1(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF1)==(DMA_LISR_TCIF1)); +} + +/** + * @brief Get Stream 2 transfer complete flag. + * @rmtoll LISR TCIF2 LL_DMA_IsActiveFlag_TC2 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC2(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF2)==(DMA_LISR_TCIF2)); +} + +/** + * @brief Get Stream 3 transfer complete flag. + * @rmtoll LISR TCIF3 LL_DMA_IsActiveFlag_TC3 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC3(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF3)==(DMA_LISR_TCIF3)); +} + +/** + * @brief Get Stream 4 transfer complete flag. + * @rmtoll HISR TCIF4 LL_DMA_IsActiveFlag_TC4 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC4(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF4)==(DMA_HISR_TCIF4)); +} + +/** + * @brief Get Stream 5 transfer complete flag. + * @rmtoll HISR TCIF0 LL_DMA_IsActiveFlag_TC5 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC5(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF5)==(DMA_HISR_TCIF5)); +} + +/** + * @brief Get Stream 6 transfer complete flag. + * @rmtoll HISR TCIF6 LL_DMA_IsActiveFlag_TC6 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC6(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF6)==(DMA_HISR_TCIF6)); +} + +/** + * @brief Get Stream 7 transfer complete flag. + * @rmtoll HISR TCIF7 LL_DMA_IsActiveFlag_TC7 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC7(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF7)==(DMA_HISR_TCIF7)); +} + +/** + * @brief Get Stream 0 transfer error flag. + * @rmtoll LISR TEIF0 LL_DMA_IsActiveFlag_TE0 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE0(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF0)==(DMA_LISR_TEIF0)); +} + +/** + * @brief Get Stream 1 transfer error flag. + * @rmtoll LISR TEIF1 LL_DMA_IsActiveFlag_TE1 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE1(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF1)==(DMA_LISR_TEIF1)); +} + +/** + * @brief Get Stream 2 transfer error flag. + * @rmtoll LISR TEIF2 LL_DMA_IsActiveFlag_TE2 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE2(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF2)==(DMA_LISR_TEIF2)); +} + +/** + * @brief Get Stream 3 transfer error flag. + * @rmtoll LISR TEIF3 LL_DMA_IsActiveFlag_TE3 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE3(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF3)==(DMA_LISR_TEIF3)); +} + +/** + * @brief Get Stream 4 transfer error flag. + * @rmtoll HISR TEIF4 LL_DMA_IsActiveFlag_TE4 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE4(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF4)==(DMA_HISR_TEIF4)); +} + +/** + * @brief Get Stream 5 transfer error flag. + * @rmtoll HISR TEIF0 LL_DMA_IsActiveFlag_TE5 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE5(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF5)==(DMA_HISR_TEIF5)); +} + +/** + * @brief Get Stream 6 transfer error flag. + * @rmtoll HISR TEIF6 LL_DMA_IsActiveFlag_TE6 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE6(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF6)==(DMA_HISR_TEIF6)); +} + +/** + * @brief Get Stream 7 transfer error flag. + * @rmtoll HISR TEIF7 LL_DMA_IsActiveFlag_TE7 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE7(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF7)==(DMA_HISR_TEIF7)); +} + +/** + * @brief Get Stream 0 direct mode error flag. + * @rmtoll LISR DMEIF0 LL_DMA_IsActiveFlag_DME0 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME0(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF0)==(DMA_LISR_DMEIF0)); +} + +/** + * @brief Get Stream 1 direct mode error flag. + * @rmtoll LISR DMEIF1 LL_DMA_IsActiveFlag_DME1 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME1(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF1)==(DMA_LISR_DMEIF1)); +} + +/** + * @brief Get Stream 2 direct mode error flag. + * @rmtoll LISR DMEIF2 LL_DMA_IsActiveFlag_DME2 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME2(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF2)==(DMA_LISR_DMEIF2)); +} + +/** + * @brief Get Stream 3 direct mode error flag. + * @rmtoll LISR DMEIF3 LL_DMA_IsActiveFlag_DME3 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME3(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF3)==(DMA_LISR_DMEIF3)); +} + +/** + * @brief Get Stream 4 direct mode error flag. + * @rmtoll HISR DMEIF4 LL_DMA_IsActiveFlag_DME4 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME4(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF4)==(DMA_HISR_DMEIF4)); +} + +/** + * @brief Get Stream 5 direct mode error flag. + * @rmtoll HISR DMEIF0 LL_DMA_IsActiveFlag_DME5 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME5(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF5)==(DMA_HISR_DMEIF5)); +} + +/** + * @brief Get Stream 6 direct mode error flag. + * @rmtoll HISR DMEIF6 LL_DMA_IsActiveFlag_DME6 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME6(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF6)==(DMA_HISR_DMEIF6)); +} + +/** + * @brief Get Stream 7 direct mode error flag. + * @rmtoll HISR DMEIF7 LL_DMA_IsActiveFlag_DME7 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME7(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF7)==(DMA_HISR_DMEIF7)); +} + +/** + * @brief Get Stream 0 FIFO error flag. + * @rmtoll LISR FEIF0 LL_DMA_IsActiveFlag_FE0 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE0(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF0)==(DMA_LISR_FEIF0)); +} + +/** + * @brief Get Stream 1 FIFO error flag. + * @rmtoll LISR FEIF1 LL_DMA_IsActiveFlag_FE1 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE1(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF1)==(DMA_LISR_FEIF1)); +} + +/** + * @brief Get Stream 2 FIFO error flag. + * @rmtoll LISR FEIF2 LL_DMA_IsActiveFlag_FE2 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE2(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF2)==(DMA_LISR_FEIF2)); +} + +/** + * @brief Get Stream 3 FIFO error flag. + * @rmtoll LISR FEIF3 LL_DMA_IsActiveFlag_FE3 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE3(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF3)==(DMA_LISR_FEIF3)); +} + +/** + * @brief Get Stream 4 FIFO error flag. + * @rmtoll HISR FEIF4 LL_DMA_IsActiveFlag_FE4 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE4(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF4)==(DMA_HISR_FEIF4)); +} + +/** + * @brief Get Stream 5 FIFO error flag. + * @rmtoll HISR FEIF0 LL_DMA_IsActiveFlag_FE5 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE5(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF5)==(DMA_HISR_FEIF5)); +} + +/** + * @brief Get Stream 6 FIFO error flag. + * @rmtoll HISR FEIF6 LL_DMA_IsActiveFlag_FE6 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE6(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF6)==(DMA_HISR_FEIF6)); +} + +/** + * @brief Get Stream 7 FIFO error flag. + * @rmtoll HISR FEIF7 LL_DMA_IsActiveFlag_FE7 + * @param DMAx DMAx Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE7(DMA_TypeDef *DMAx) +{ + return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF7)==(DMA_HISR_FEIF7)); +} + +/** + * @brief Clear Stream 0 half transfer flag. + * @rmtoll LIFCR CHTIF0 LL_DMA_ClearFlag_HT0 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT0(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF0); +} + +/** + * @brief Clear Stream 1 half transfer flag. + * @rmtoll LIFCR CHTIF1 LL_DMA_ClearFlag_HT1 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT1(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF1); +} + +/** + * @brief Clear Stream 2 half transfer flag. + * @rmtoll LIFCR CHTIF2 LL_DMA_ClearFlag_HT2 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT2(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF2); +} + +/** + * @brief Clear Stream 3 half transfer flag. + * @rmtoll LIFCR CHTIF3 LL_DMA_ClearFlag_HT3 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT3(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF3); +} + +/** + * @brief Clear Stream 4 half transfer flag. + * @rmtoll HIFCR CHTIF4 LL_DMA_ClearFlag_HT4 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT4(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF4); +} + +/** + * @brief Clear Stream 5 half transfer flag. + * @rmtoll HIFCR CHTIF5 LL_DMA_ClearFlag_HT5 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT5(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF5); +} + +/** + * @brief Clear Stream 6 half transfer flag. + * @rmtoll HIFCR CHTIF6 LL_DMA_ClearFlag_HT6 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT6(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF6); +} + +/** + * @brief Clear Stream 7 half transfer flag. + * @rmtoll HIFCR CHTIF7 LL_DMA_ClearFlag_HT7 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_HT7(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF7); +} + +/** + * @brief Clear Stream 0 transfer complete flag. + * @rmtoll LIFCR CTCIF0 LL_DMA_ClearFlag_TC0 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC0(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF0); +} + +/** + * @brief Clear Stream 1 transfer complete flag. + * @rmtoll LIFCR CTCIF1 LL_DMA_ClearFlag_TC1 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC1(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF1); +} + +/** + * @brief Clear Stream 2 transfer complete flag. + * @rmtoll LIFCR CTCIF2 LL_DMA_ClearFlag_TC2 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC2(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF2); +} + +/** + * @brief Clear Stream 3 transfer complete flag. + * @rmtoll LIFCR CTCIF3 LL_DMA_ClearFlag_TC3 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC3(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF3); +} + +/** + * @brief Clear Stream 4 transfer complete flag. + * @rmtoll HIFCR CTCIF4 LL_DMA_ClearFlag_TC4 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC4(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF4); +} + +/** + * @brief Clear Stream 5 transfer complete flag. + * @rmtoll HIFCR CTCIF5 LL_DMA_ClearFlag_TC5 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC5(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF5); +} + +/** + * @brief Clear Stream 6 transfer complete flag. + * @rmtoll HIFCR CTCIF6 LL_DMA_ClearFlag_TC6 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC6(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF6); +} + +/** + * @brief Clear Stream 7 transfer complete flag. + * @rmtoll HIFCR CTCIF7 LL_DMA_ClearFlag_TC7 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TC7(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF7); +} + +/** + * @brief Clear Stream 0 transfer error flag. + * @rmtoll LIFCR CTEIF0 LL_DMA_ClearFlag_TE0 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE0(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF0); +} + +/** + * @brief Clear Stream 1 transfer error flag. + * @rmtoll LIFCR CTEIF1 LL_DMA_ClearFlag_TE1 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE1(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF1); +} + +/** + * @brief Clear Stream 2 transfer error flag. + * @rmtoll LIFCR CTEIF2 LL_DMA_ClearFlag_TE2 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE2(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF2); +} + +/** + * @brief Clear Stream 3 transfer error flag. + * @rmtoll LIFCR CTEIF3 LL_DMA_ClearFlag_TE3 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE3(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF3); +} + +/** + * @brief Clear Stream 4 transfer error flag. + * @rmtoll HIFCR CTEIF4 LL_DMA_ClearFlag_TE4 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE4(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF4); +} + +/** + * @brief Clear Stream 5 transfer error flag. + * @rmtoll HIFCR CTEIF5 LL_DMA_ClearFlag_TE5 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE5(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF5); +} + +/** + * @brief Clear Stream 6 transfer error flag. + * @rmtoll HIFCR CTEIF6 LL_DMA_ClearFlag_TE6 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE6(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF6); +} + +/** + * @brief Clear Stream 7 transfer error flag. + * @rmtoll HIFCR CTEIF7 LL_DMA_ClearFlag_TE7 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_TE7(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF7); +} + +/** + * @brief Clear Stream 0 direct mode error flag. + * @rmtoll LIFCR CDMEIF0 LL_DMA_ClearFlag_DME0 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME0(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF0); +} + +/** + * @brief Clear Stream 1 direct mode error flag. + * @rmtoll LIFCR CDMEIF1 LL_DMA_ClearFlag_DME1 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME1(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF1); +} + +/** + * @brief Clear Stream 2 direct mode error flag. + * @rmtoll LIFCR CDMEIF2 LL_DMA_ClearFlag_DME2 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME2(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF2); +} + +/** + * @brief Clear Stream 3 direct mode error flag. + * @rmtoll LIFCR CDMEIF3 LL_DMA_ClearFlag_DME3 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME3(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF3); +} + +/** + * @brief Clear Stream 4 direct mode error flag. + * @rmtoll HIFCR CDMEIF4 LL_DMA_ClearFlag_DME4 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME4(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF4); +} + +/** + * @brief Clear Stream 5 direct mode error flag. + * @rmtoll HIFCR CDMEIF5 LL_DMA_ClearFlag_DME5 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME5(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF5); +} + +/** + * @brief Clear Stream 6 direct mode error flag. + * @rmtoll HIFCR CDMEIF6 LL_DMA_ClearFlag_DME6 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME6(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF6); +} + +/** + * @brief Clear Stream 7 direct mode error flag. + * @rmtoll HIFCR CDMEIF7 LL_DMA_ClearFlag_DME7 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_DME7(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF7); +} + +/** + * @brief Clear Stream 0 FIFO error flag. + * @rmtoll LIFCR CFEIF0 LL_DMA_ClearFlag_FE0 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE0(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF0); +} + +/** + * @brief Clear Stream 1 FIFO error flag. + * @rmtoll LIFCR CFEIF1 LL_DMA_ClearFlag_FE1 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE1(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF1); +} + +/** + * @brief Clear Stream 2 FIFO error flag. + * @rmtoll LIFCR CFEIF2 LL_DMA_ClearFlag_FE2 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE2(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF2); +} + +/** + * @brief Clear Stream 3 FIFO error flag. + * @rmtoll LIFCR CFEIF3 LL_DMA_ClearFlag_FE3 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE3(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF3); +} + +/** + * @brief Clear Stream 4 FIFO error flag. + * @rmtoll HIFCR CFEIF4 LL_DMA_ClearFlag_FE4 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE4(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF4); +} + +/** + * @brief Clear Stream 5 FIFO error flag. + * @rmtoll HIFCR CFEIF5 LL_DMA_ClearFlag_FE5 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE5(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF5); +} + +/** + * @brief Clear Stream 6 FIFO error flag. + * @rmtoll HIFCR CFEIF6 LL_DMA_ClearFlag_FE6 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE6(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF6); +} + +/** + * @brief Clear Stream 7 FIFO error flag. + * @rmtoll HIFCR CFEIF7 LL_DMA_ClearFlag_FE7 + * @param DMAx DMAx Instance + * @retval None + */ +__STATIC_INLINE void LL_DMA_ClearFlag_FE7(DMA_TypeDef *DMAx) +{ + WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF7); +} + +/** + * @} + */ + +/** @defgroup DMA_LL_EF_IT_Management IT_Management + * @{ + */ + +/** + * @brief Enable Half transfer interrupt. + * @rmtoll CR HTIE LL_DMA_EnableIT_HT + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); +} + +/** + * @brief Enable Transfer error interrupt. + * @rmtoll CR TEIE LL_DMA_EnableIT_TE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); +} + +/** + * @brief Enable Transfer complete interrupt. + * @rmtoll CR TCIE LL_DMA_EnableIT_TC + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); +} + +/** + * @brief Enable Direct mode error interrupt. + * @rmtoll CR DMEIE LL_DMA_EnableIT_DME + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); +} + +/** + * @brief Enable FIFO error interrupt. + * @rmtoll FCR FEIE LL_DMA_EnableIT_FE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_EnableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); +} + +/** + * @brief Disable Half transfer interrupt. + * @rmtoll CR HTIE LL_DMA_DisableIT_HT + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); +} + +/** + * @brief Disable Transfer error interrupt. + * @rmtoll CR TEIE LL_DMA_DisableIT_TE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); +} + +/** + * @brief Disable Transfer complete interrupt. + * @rmtoll CR TCIE LL_DMA_DisableIT_TC + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); +} + +/** + * @brief Disable Direct mode error interrupt. + * @rmtoll CR DMEIE LL_DMA_DisableIT_DME + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); +} + +/** + * @brief Disable FIFO error interrupt. + * @rmtoll FCR FEIE LL_DMA_DisableIT_FE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval None + */ +__STATIC_INLINE void LL_DMA_DisableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); +} + +/** + * @brief Check if Half transfer interrupt is enabled. + * @rmtoll CR HTIE LL_DMA_IsEnabledIT_HT + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE) == DMA_SxCR_HTIE); +} + +/** + * @brief Check if Transfer error nterrup is enabled. + * @rmtoll CR TEIE LL_DMA_IsEnabledIT_TE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE) == DMA_SxCR_TEIE); +} + +/** + * @brief Check if Transfer complete interrupt is enabled. + * @rmtoll CR TCIE LL_DMA_IsEnabledIT_TC + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE) == DMA_SxCR_TCIE); +} + +/** + * @brief Check if Direct mode error interrupt is enabled. + * @rmtoll CR DMEIE LL_DMA_IsEnabledIT_DME + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE) == DMA_SxCR_DMEIE); +} + +/** + * @brief Check if FIFO error interrupt is enabled. + * @rmtoll FCR FEIE LL_DMA_IsEnabledIT_FE + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) +{ + return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE) == DMA_SxFCR_FEIE); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup DMA_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct); +uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream); +void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct); + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DMA1 || DMA2 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_DMA_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h index 65ab691..bef8894 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h @@ -1,954 +1,954 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_exti.h - * @author MCD Application Team - * @brief Header file of EXTI LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS.Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_EXTI_H -#define __STM32F4xx_LL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (EXTI) - -/** @defgroup EXTI_LL EXTI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private Macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_Private_Macros EXTI Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_ES_INIT EXTI Exported Init structure - * @{ - */ -typedef struct -{ - - uint32_t Line_0_31; /*!< Specifies the EXTI lines to be enabled or disabled for Lines in range 0 to 31 - This parameter can be any combination of @ref EXTI_LL_EC_LINE */ - - FunctionalState LineCommand; /*!< Specifies the new state of the selected EXTI lines. - This parameter can be set either to ENABLE or DISABLE */ - - uint8_t Mode; /*!< Specifies the mode for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_MODE. */ - - uint8_t Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_TRIGGER. */ -} LL_EXTI_InitTypeDef; - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_LL_EC_LINE LINE - * @{ - */ -#define LL_EXTI_LINE_0 EXTI_IMR_IM0 /*!< Extended line 0 */ -#define LL_EXTI_LINE_1 EXTI_IMR_IM1 /*!< Extended line 1 */ -#define LL_EXTI_LINE_2 EXTI_IMR_IM2 /*!< Extended line 2 */ -#define LL_EXTI_LINE_3 EXTI_IMR_IM3 /*!< Extended line 3 */ -#define LL_EXTI_LINE_4 EXTI_IMR_IM4 /*!< Extended line 4 */ -#define LL_EXTI_LINE_5 EXTI_IMR_IM5 /*!< Extended line 5 */ -#define LL_EXTI_LINE_6 EXTI_IMR_IM6 /*!< Extended line 6 */ -#define LL_EXTI_LINE_7 EXTI_IMR_IM7 /*!< Extended line 7 */ -#define LL_EXTI_LINE_8 EXTI_IMR_IM8 /*!< Extended line 8 */ -#define LL_EXTI_LINE_9 EXTI_IMR_IM9 /*!< Extended line 9 */ -#define LL_EXTI_LINE_10 EXTI_IMR_IM10 /*!< Extended line 10 */ -#define LL_EXTI_LINE_11 EXTI_IMR_IM11 /*!< Extended line 11 */ -#define LL_EXTI_LINE_12 EXTI_IMR_IM12 /*!< Extended line 12 */ -#define LL_EXTI_LINE_13 EXTI_IMR_IM13 /*!< Extended line 13 */ -#define LL_EXTI_LINE_14 EXTI_IMR_IM14 /*!< Extended line 14 */ -#define LL_EXTI_LINE_15 EXTI_IMR_IM15 /*!< Extended line 15 */ -#if defined(EXTI_IMR_IM16) -#define LL_EXTI_LINE_16 EXTI_IMR_IM16 /*!< Extended line 16 */ -#endif -#define LL_EXTI_LINE_17 EXTI_IMR_IM17 /*!< Extended line 17 */ -#if defined(EXTI_IMR_IM18) -#define LL_EXTI_LINE_18 EXTI_IMR_IM18 /*!< Extended line 18 */ -#endif -#define LL_EXTI_LINE_19 EXTI_IMR_IM19 /*!< Extended line 19 */ -#if defined(EXTI_IMR_IM20) -#define LL_EXTI_LINE_20 EXTI_IMR_IM20 /*!< Extended line 20 */ -#endif -#if defined(EXTI_IMR_IM21) -#define LL_EXTI_LINE_21 EXTI_IMR_IM21 /*!< Extended line 21 */ -#endif -#if defined(EXTI_IMR_IM22) -#define LL_EXTI_LINE_22 EXTI_IMR_IM22 /*!< Extended line 22 */ -#endif -#if defined(EXTI_IMR_IM23) -#define LL_EXTI_LINE_23 EXTI_IMR_IM23 /*!< Extended line 23 */ -#endif -#if defined(EXTI_IMR_IM24) -#define LL_EXTI_LINE_24 EXTI_IMR_IM24 /*!< Extended line 24 */ -#endif -#if defined(EXTI_IMR_IM25) -#define LL_EXTI_LINE_25 EXTI_IMR_IM25 /*!< Extended line 25 */ -#endif -#if defined(EXTI_IMR_IM26) -#define LL_EXTI_LINE_26 EXTI_IMR_IM26 /*!< Extended line 26 */ -#endif -#if defined(EXTI_IMR_IM27) -#define LL_EXTI_LINE_27 EXTI_IMR_IM27 /*!< Extended line 27 */ -#endif -#if defined(EXTI_IMR_IM28) -#define LL_EXTI_LINE_28 EXTI_IMR_IM28 /*!< Extended line 28 */ -#endif -#if defined(EXTI_IMR_IM29) -#define LL_EXTI_LINE_29 EXTI_IMR_IM29 /*!< Extended line 29 */ -#endif -#if defined(EXTI_IMR_IM30) -#define LL_EXTI_LINE_30 EXTI_IMR_IM30 /*!< Extended line 30 */ -#endif -#if defined(EXTI_IMR_IM31) -#define LL_EXTI_LINE_31 EXTI_IMR_IM31 /*!< Extended line 31 */ -#endif -#define LL_EXTI_LINE_ALL_0_31 EXTI_IMR_IM /*!< All Extended line not reserved*/ - - -#define LL_EXTI_LINE_ALL ((uint32_t)0xFFFFFFFFU) /*!< All Extended line */ - -#if defined(USE_FULL_LL_DRIVER) -#define LL_EXTI_LINE_NONE ((uint32_t)0x00000000U) /*!< None Extended line */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup EXTI_LL_EC_MODE Mode - * @{ - */ -#define LL_EXTI_MODE_IT ((uint8_t)0x00U) /*!< Interrupt Mode */ -#define LL_EXTI_MODE_EVENT ((uint8_t)0x01U) /*!< Event Mode */ -#define LL_EXTI_MODE_IT_EVENT ((uint8_t)0x02U) /*!< Interrupt & Event Mode */ -/** - * @} - */ - -/** @defgroup EXTI_LL_EC_TRIGGER Edge Trigger - * @{ - */ -#define LL_EXTI_TRIGGER_NONE ((uint8_t)0x00U) /*!< No Trigger Mode */ -#define LL_EXTI_TRIGGER_RISING ((uint8_t)0x01U) /*!< Trigger Rising Mode */ -#define LL_EXTI_TRIGGER_FALLING ((uint8_t)0x02U) /*!< Trigger Falling Mode */ -#define LL_EXTI_TRIGGER_RISING_FALLING ((uint8_t)0x03U) /*!< Trigger Rising & Falling Mode */ - -/** - * @} - */ - - -#endif /*USE_FULL_LL_DRIVER*/ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** @defgroup EXTI_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in EXTI register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_EXTI_WriteReg(__REG__, __VALUE__) WRITE_REG(EXTI->__REG__, (__VALUE__)) - -/** - * @brief Read a value in EXTI register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_EXTI_ReadReg(__REG__) READ_REG(EXTI->__REG__) -/** - * @} - */ - - -/** - * @} - */ - - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Functions EXTI Exported Functions - * @{ - */ -/** @defgroup EXTI_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_EnableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableIT_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->IMR, ExtiLine); -} - -/** - * @brief Disable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_DisableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableIT_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->IMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Interrupt request is enabled for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_IsEnabledIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledIT_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->IMR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Event_Management Event_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_EnableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableEvent_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->EMR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_DisableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableEvent_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->EMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Event request is enabled for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_IsEnabledEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledEvent_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->EMR, ExtiLine) == (ExtiLine)); - -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Rising_Trigger_Management Rising_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_EnableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableRisingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_DisableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableRisingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Check if rising edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll RTSR RTx LL_EXTI_IsEnabledRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledRisingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->RTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Falling_Trigger_Management Falling_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll FTSR FTx LL_EXTI_EnableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableFallingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Disable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a Falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for the same interrupt line. - * In this case, both generate a trigger condition. - * @rmtoll FTSR FTx LL_EXTI_DisableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableFallingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Check if falling edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll FTSR FTx LL_EXTI_IsEnabledFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledFallingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->FTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Software_Interrupt_Management Software_Interrupt_Management - * @{ - */ - -/** - * @brief Generate a software Interrupt Event for Lines in range 0 to 31 - * @note If the interrupt is enabled on this line in the EXTI_IMR, writing a 1 to - * this bit when it is at '0' sets the corresponding pending bit in EXTI_PR - * resulting in an interrupt request generation. - * This bit is cleared by clearing the corresponding bit in the EXTI_PR - * register (by writing a 1 into the bit) - * @rmtoll SWIER SWIx LL_EXTI_GenerateSWI_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_GenerateSWI_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->SWIER, ExtiLine); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Flag_Management Flag_Management - * @{ - */ - -/** - * @brief Check if the ExtLine Flag is set or not for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_IsActiveFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsActiveFlag_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->PR, ExtiLine) == (ExtiLine)); -} - - -/** - * @brief Read ExtLine Combination Flag for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ReadFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval @note This bit is set when the selected edge event arrives on the interrupt - */ -__STATIC_INLINE uint32_t LL_EXTI_ReadFlag_0_31(uint32_t ExtiLine) -{ - return (uint32_t)(READ_BIT(EXTI->PR, ExtiLine)); -} - - -/** - * @brief Clear ExtLine Flags for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ClearFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_ClearFlag_0_31(uint32_t ExtiLine) -{ - WRITE_REG(EXTI->PR, ExtiLine); -} - - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct); -uint32_t LL_EXTI_DeInit(void); -void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* EXTI */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_EXTI_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_exti.h + * @author MCD Application Team + * @brief Header file of EXTI LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS.Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_EXTI_H +#define __STM32F4xx_LL_EXTI_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (EXTI) + +/** @defgroup EXTI_LL EXTI + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private Macros ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup EXTI_LL_Private_Macros EXTI Private Macros + * @{ + */ +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup EXTI_LL_ES_INIT EXTI Exported Init structure + * @{ + */ +typedef struct +{ + + uint32_t Line_0_31; /*!< Specifies the EXTI lines to be enabled or disabled for Lines in range 0 to 31 + This parameter can be any combination of @ref EXTI_LL_EC_LINE */ + + FunctionalState LineCommand; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ + + uint8_t Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTI_LL_EC_MODE. */ + + uint8_t Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTI_LL_EC_TRIGGER. */ +} LL_EXTI_InitTypeDef; + +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup EXTI_LL_Exported_Constants EXTI Exported Constants + * @{ + */ + +/** @defgroup EXTI_LL_EC_LINE LINE + * @{ + */ +#define LL_EXTI_LINE_0 EXTI_IMR_IM0 /*!< Extended line 0 */ +#define LL_EXTI_LINE_1 EXTI_IMR_IM1 /*!< Extended line 1 */ +#define LL_EXTI_LINE_2 EXTI_IMR_IM2 /*!< Extended line 2 */ +#define LL_EXTI_LINE_3 EXTI_IMR_IM3 /*!< Extended line 3 */ +#define LL_EXTI_LINE_4 EXTI_IMR_IM4 /*!< Extended line 4 */ +#define LL_EXTI_LINE_5 EXTI_IMR_IM5 /*!< Extended line 5 */ +#define LL_EXTI_LINE_6 EXTI_IMR_IM6 /*!< Extended line 6 */ +#define LL_EXTI_LINE_7 EXTI_IMR_IM7 /*!< Extended line 7 */ +#define LL_EXTI_LINE_8 EXTI_IMR_IM8 /*!< Extended line 8 */ +#define LL_EXTI_LINE_9 EXTI_IMR_IM9 /*!< Extended line 9 */ +#define LL_EXTI_LINE_10 EXTI_IMR_IM10 /*!< Extended line 10 */ +#define LL_EXTI_LINE_11 EXTI_IMR_IM11 /*!< Extended line 11 */ +#define LL_EXTI_LINE_12 EXTI_IMR_IM12 /*!< Extended line 12 */ +#define LL_EXTI_LINE_13 EXTI_IMR_IM13 /*!< Extended line 13 */ +#define LL_EXTI_LINE_14 EXTI_IMR_IM14 /*!< Extended line 14 */ +#define LL_EXTI_LINE_15 EXTI_IMR_IM15 /*!< Extended line 15 */ +#if defined(EXTI_IMR_IM16) +#define LL_EXTI_LINE_16 EXTI_IMR_IM16 /*!< Extended line 16 */ +#endif +#define LL_EXTI_LINE_17 EXTI_IMR_IM17 /*!< Extended line 17 */ +#if defined(EXTI_IMR_IM18) +#define LL_EXTI_LINE_18 EXTI_IMR_IM18 /*!< Extended line 18 */ +#endif +#define LL_EXTI_LINE_19 EXTI_IMR_IM19 /*!< Extended line 19 */ +#if defined(EXTI_IMR_IM20) +#define LL_EXTI_LINE_20 EXTI_IMR_IM20 /*!< Extended line 20 */ +#endif +#if defined(EXTI_IMR_IM21) +#define LL_EXTI_LINE_21 EXTI_IMR_IM21 /*!< Extended line 21 */ +#endif +#if defined(EXTI_IMR_IM22) +#define LL_EXTI_LINE_22 EXTI_IMR_IM22 /*!< Extended line 22 */ +#endif +#if defined(EXTI_IMR_IM23) +#define LL_EXTI_LINE_23 EXTI_IMR_IM23 /*!< Extended line 23 */ +#endif +#if defined(EXTI_IMR_IM24) +#define LL_EXTI_LINE_24 EXTI_IMR_IM24 /*!< Extended line 24 */ +#endif +#if defined(EXTI_IMR_IM25) +#define LL_EXTI_LINE_25 EXTI_IMR_IM25 /*!< Extended line 25 */ +#endif +#if defined(EXTI_IMR_IM26) +#define LL_EXTI_LINE_26 EXTI_IMR_IM26 /*!< Extended line 26 */ +#endif +#if defined(EXTI_IMR_IM27) +#define LL_EXTI_LINE_27 EXTI_IMR_IM27 /*!< Extended line 27 */ +#endif +#if defined(EXTI_IMR_IM28) +#define LL_EXTI_LINE_28 EXTI_IMR_IM28 /*!< Extended line 28 */ +#endif +#if defined(EXTI_IMR_IM29) +#define LL_EXTI_LINE_29 EXTI_IMR_IM29 /*!< Extended line 29 */ +#endif +#if defined(EXTI_IMR_IM30) +#define LL_EXTI_LINE_30 EXTI_IMR_IM30 /*!< Extended line 30 */ +#endif +#if defined(EXTI_IMR_IM31) +#define LL_EXTI_LINE_31 EXTI_IMR_IM31 /*!< Extended line 31 */ +#endif +#define LL_EXTI_LINE_ALL_0_31 EXTI_IMR_IM /*!< All Extended line not reserved*/ + + +#define LL_EXTI_LINE_ALL ((uint32_t)0xFFFFFFFFU) /*!< All Extended line */ + +#if defined(USE_FULL_LL_DRIVER) +#define LL_EXTI_LINE_NONE ((uint32_t)0x00000000U) /*!< None Extended line */ +#endif /*USE_FULL_LL_DRIVER*/ + +/** + * @} + */ +#if defined(USE_FULL_LL_DRIVER) + +/** @defgroup EXTI_LL_EC_MODE Mode + * @{ + */ +#define LL_EXTI_MODE_IT ((uint8_t)0x00U) /*!< Interrupt Mode */ +#define LL_EXTI_MODE_EVENT ((uint8_t)0x01U) /*!< Event Mode */ +#define LL_EXTI_MODE_IT_EVENT ((uint8_t)0x02U) /*!< Interrupt & Event Mode */ +/** + * @} + */ + +/** @defgroup EXTI_LL_EC_TRIGGER Edge Trigger + * @{ + */ +#define LL_EXTI_TRIGGER_NONE ((uint8_t)0x00U) /*!< No Trigger Mode */ +#define LL_EXTI_TRIGGER_RISING ((uint8_t)0x01U) /*!< Trigger Rising Mode */ +#define LL_EXTI_TRIGGER_FALLING ((uint8_t)0x02U) /*!< Trigger Falling Mode */ +#define LL_EXTI_TRIGGER_RISING_FALLING ((uint8_t)0x03U) /*!< Trigger Rising & Falling Mode */ + +/** + * @} + */ + + +#endif /*USE_FULL_LL_DRIVER*/ + + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup EXTI_LL_Exported_Macros EXTI Exported Macros + * @{ + */ + +/** @defgroup EXTI_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in EXTI register + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_EXTI_WriteReg(__REG__, __VALUE__) WRITE_REG(EXTI->__REG__, (__VALUE__)) + +/** + * @brief Read a value in EXTI register + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_EXTI_ReadReg(__REG__) READ_REG(EXTI->__REG__) +/** + * @} + */ + + +/** + * @} + */ + + + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup EXTI_LL_Exported_Functions EXTI Exported Functions + * @{ + */ +/** @defgroup EXTI_LL_EF_IT_Management IT_Management + * @{ + */ + +/** + * @brief Enable ExtiLine Interrupt request for Lines in range 0 to 31 + * @note The reset value for the direct or internal lines (see RM) + * is set to 1 in order to enable the interrupt by default. + * Bits are set automatically at Power on. + * @rmtoll IMR IMx LL_EXTI_EnableIT_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_EnableIT_0_31(uint32_t ExtiLine) +{ + SET_BIT(EXTI->IMR, ExtiLine); +} + +/** + * @brief Disable ExtiLine Interrupt request for Lines in range 0 to 31 + * @note The reset value for the direct or internal lines (see RM) + * is set to 1 in order to enable the interrupt by default. + * Bits are set automatically at Power on. + * @rmtoll IMR IMx LL_EXTI_DisableIT_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_DisableIT_0_31(uint32_t ExtiLine) +{ + CLEAR_BIT(EXTI->IMR, ExtiLine); +} + + +/** + * @brief Indicate if ExtiLine Interrupt request is enabled for Lines in range 0 to 31 + * @note The reset value for the direct or internal lines (see RM) + * is set to 1 in order to enable the interrupt by default. + * Bits are set automatically at Power on. + * @rmtoll IMR IMx LL_EXTI_IsEnabledIT_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_EXTI_IsEnabledIT_0_31(uint32_t ExtiLine) +{ + return (READ_BIT(EXTI->IMR, ExtiLine) == (ExtiLine)); +} + + +/** + * @} + */ + +/** @defgroup EXTI_LL_EF_Event_Management Event_Management + * @{ + */ + +/** + * @brief Enable ExtiLine Event request for Lines in range 0 to 31 + * @rmtoll EMR EMx LL_EXTI_EnableEvent_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_EnableEvent_0_31(uint32_t ExtiLine) +{ + SET_BIT(EXTI->EMR, ExtiLine); + +} + + +/** + * @brief Disable ExtiLine Event request for Lines in range 0 to 31 + * @rmtoll EMR EMx LL_EXTI_DisableEvent_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_DisableEvent_0_31(uint32_t ExtiLine) +{ + CLEAR_BIT(EXTI->EMR, ExtiLine); +} + + +/** + * @brief Indicate if ExtiLine Event request is enabled for Lines in range 0 to 31 + * @rmtoll EMR EMx LL_EXTI_IsEnabledEvent_0_31 + * @param ExtiLine This parameter can be one of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_17 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @arg @ref LL_EXTI_LINE_23(*) + * @arg @ref LL_EXTI_LINE_ALL_0_31 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_EXTI_IsEnabledEvent_0_31(uint32_t ExtiLine) +{ + return (READ_BIT(EXTI->EMR, ExtiLine) == (ExtiLine)); + +} + + +/** + * @} + */ + +/** @defgroup EXTI_LL_EF_Rising_Trigger_Management Rising_Trigger_Management + * @{ + */ + +/** + * @brief Enable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 + * @note The configurable wakeup lines are edge-triggered. No glitch must be + * generated on these lines. If a rising edge on a configurable interrupt + * line occurs during a write operation in the EXTI_RTSR register, the + * pending bit is not set. + * Rising and falling edge triggers can be set for + * the same interrupt line. In this case, both generate a trigger + * condition. + * @rmtoll RTSR RTx LL_EXTI_EnableRisingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_EnableRisingTrig_0_31(uint32_t ExtiLine) +{ + SET_BIT(EXTI->RTSR, ExtiLine); + +} + + +/** + * @brief Disable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 + * @note The configurable wakeup lines are edge-triggered. No glitch must be + * generated on these lines. If a rising edge on a configurable interrupt + * line occurs during a write operation in the EXTI_RTSR register, the + * pending bit is not set. + * Rising and falling edge triggers can be set for + * the same interrupt line. In this case, both generate a trigger + * condition. + * @rmtoll RTSR RTx LL_EXTI_DisableRisingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_DisableRisingTrig_0_31(uint32_t ExtiLine) +{ + CLEAR_BIT(EXTI->RTSR, ExtiLine); + +} + + +/** + * @brief Check if rising edge trigger is enabled for Lines in range 0 to 31 + * @rmtoll RTSR RTx LL_EXTI_IsEnabledRisingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_EXTI_IsEnabledRisingTrig_0_31(uint32_t ExtiLine) +{ + return (READ_BIT(EXTI->RTSR, ExtiLine) == (ExtiLine)); +} + + +/** + * @} + */ + +/** @defgroup EXTI_LL_EF_Falling_Trigger_Management Falling_Trigger_Management + * @{ + */ + +/** + * @brief Enable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 + * @note The configurable wakeup lines are edge-triggered. No glitch must be + * generated on these lines. If a falling edge on a configurable interrupt + * line occurs during a write operation in the EXTI_FTSR register, the + * pending bit is not set. + * Rising and falling edge triggers can be set for + * the same interrupt line. In this case, both generate a trigger + * condition. + * @rmtoll FTSR FTx LL_EXTI_EnableFallingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_EnableFallingTrig_0_31(uint32_t ExtiLine) +{ + SET_BIT(EXTI->FTSR, ExtiLine); +} + + +/** + * @brief Disable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 + * @note The configurable wakeup lines are edge-triggered. No glitch must be + * generated on these lines. If a Falling edge on a configurable interrupt + * line occurs during a write operation in the EXTI_FTSR register, the + * pending bit is not set. + * Rising and falling edge triggers can be set for the same interrupt line. + * In this case, both generate a trigger condition. + * @rmtoll FTSR FTx LL_EXTI_DisableFallingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_DisableFallingTrig_0_31(uint32_t ExtiLine) +{ + CLEAR_BIT(EXTI->FTSR, ExtiLine); +} + + +/** + * @brief Check if falling edge trigger is enabled for Lines in range 0 to 31 + * @rmtoll FTSR FTx LL_EXTI_IsEnabledFallingTrig_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_EXTI_IsEnabledFallingTrig_0_31(uint32_t ExtiLine) +{ + return (READ_BIT(EXTI->FTSR, ExtiLine) == (ExtiLine)); +} + + +/** + * @} + */ + +/** @defgroup EXTI_LL_EF_Software_Interrupt_Management Software_Interrupt_Management + * @{ + */ + +/** + * @brief Generate a software Interrupt Event for Lines in range 0 to 31 + * @note If the interrupt is enabled on this line in the EXTI_IMR, writing a 1 to + * this bit when it is at '0' sets the corresponding pending bit in EXTI_PR + * resulting in an interrupt request generation. + * This bit is cleared by clearing the corresponding bit in the EXTI_PR + * register (by writing a 1 into the bit) + * @rmtoll SWIER SWIx LL_EXTI_GenerateSWI_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_GenerateSWI_0_31(uint32_t ExtiLine) +{ + SET_BIT(EXTI->SWIER, ExtiLine); +} + + +/** + * @} + */ + +/** @defgroup EXTI_LL_EF_Flag_Management Flag_Management + * @{ + */ + +/** + * @brief Check if the ExtLine Flag is set or not for Lines in range 0 to 31 + * @note This bit is set when the selected edge event arrives on the interrupt + * line. This bit is cleared by writing a 1 to the bit. + * @rmtoll PR PIFx LL_EXTI_IsActiveFlag_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_EXTI_IsActiveFlag_0_31(uint32_t ExtiLine) +{ + return (READ_BIT(EXTI->PR, ExtiLine) == (ExtiLine)); +} + + +/** + * @brief Read ExtLine Combination Flag for Lines in range 0 to 31 + * @note This bit is set when the selected edge event arrives on the interrupt + * line. This bit is cleared by writing a 1 to the bit. + * @rmtoll PR PIFx LL_EXTI_ReadFlag_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval @note This bit is set when the selected edge event arrives on the interrupt + */ +__STATIC_INLINE uint32_t LL_EXTI_ReadFlag_0_31(uint32_t ExtiLine) +{ + return (uint32_t)(READ_BIT(EXTI->PR, ExtiLine)); +} + + +/** + * @brief Clear ExtLine Flags for Lines in range 0 to 31 + * @note This bit is set when the selected edge event arrives on the interrupt + * line. This bit is cleared by writing a 1 to the bit. + * @rmtoll PR PIFx LL_EXTI_ClearFlag_0_31 + * @param ExtiLine This parameter can be a combination of the following values: + * @arg @ref LL_EXTI_LINE_0 + * @arg @ref LL_EXTI_LINE_1 + * @arg @ref LL_EXTI_LINE_2 + * @arg @ref LL_EXTI_LINE_3 + * @arg @ref LL_EXTI_LINE_4 + * @arg @ref LL_EXTI_LINE_5 + * @arg @ref LL_EXTI_LINE_6 + * @arg @ref LL_EXTI_LINE_7 + * @arg @ref LL_EXTI_LINE_8 + * @arg @ref LL_EXTI_LINE_9 + * @arg @ref LL_EXTI_LINE_10 + * @arg @ref LL_EXTI_LINE_11 + * @arg @ref LL_EXTI_LINE_12 + * @arg @ref LL_EXTI_LINE_13 + * @arg @ref LL_EXTI_LINE_14 + * @arg @ref LL_EXTI_LINE_15 + * @arg @ref LL_EXTI_LINE_16 + * @arg @ref LL_EXTI_LINE_18 + * @arg @ref LL_EXTI_LINE_19(*) + * @arg @ref LL_EXTI_LINE_20(*) + * @arg @ref LL_EXTI_LINE_21 + * @arg @ref LL_EXTI_LINE_22 + * @note (*): Available in some devices + * @note Please check each device line mapping for EXTI Line availability + * @retval None + */ +__STATIC_INLINE void LL_EXTI_ClearFlag_0_31(uint32_t ExtiLine) +{ + WRITE_REG(EXTI->PR, ExtiLine); +} + + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup EXTI_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct); +uint32_t LL_EXTI_DeInit(void); +void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct); + + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* EXTI */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_EXTI_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h index 6bee7fd..9d5b34c 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h @@ -1,981 +1,981 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_GPIO_H -#define __STM32F4xx_LL_GPIO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) - -/** @defgroup GPIO_LL GPIO - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_Private_Macros GPIO Private Macros - * @{ - */ - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_ES_INIT GPIO Exported Init structures - * @{ - */ - -/** - * @brief LL GPIO Init Structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_LL_EC_PIN */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_MODE. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinMode().*/ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_SPEED. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinSpeed().*/ - - uint32_t OutputType; /*!< Specifies the operating output type for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_OUTPUT. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinOutputType().*/ - - uint32_t Pull; /*!< Specifies the operating Pull-up/Pull down for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_PULL. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinPull().*/ - - uint32_t Alternate; /*!< Specifies the Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_AF. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetAFPin_0_7() and LL_GPIO_SetAFPin_8_15().*/ -} LL_GPIO_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_LL_EC_PIN PIN - * @{ - */ -#define LL_GPIO_PIN_0 GPIO_BSRR_BS_0 /*!< Select pin 0 */ -#define LL_GPIO_PIN_1 GPIO_BSRR_BS_1 /*!< Select pin 1 */ -#define LL_GPIO_PIN_2 GPIO_BSRR_BS_2 /*!< Select pin 2 */ -#define LL_GPIO_PIN_3 GPIO_BSRR_BS_3 /*!< Select pin 3 */ -#define LL_GPIO_PIN_4 GPIO_BSRR_BS_4 /*!< Select pin 4 */ -#define LL_GPIO_PIN_5 GPIO_BSRR_BS_5 /*!< Select pin 5 */ -#define LL_GPIO_PIN_6 GPIO_BSRR_BS_6 /*!< Select pin 6 */ -#define LL_GPIO_PIN_7 GPIO_BSRR_BS_7 /*!< Select pin 7 */ -#define LL_GPIO_PIN_8 GPIO_BSRR_BS_8 /*!< Select pin 8 */ -#define LL_GPIO_PIN_9 GPIO_BSRR_BS_9 /*!< Select pin 9 */ -#define LL_GPIO_PIN_10 GPIO_BSRR_BS_10 /*!< Select pin 10 */ -#define LL_GPIO_PIN_11 GPIO_BSRR_BS_11 /*!< Select pin 11 */ -#define LL_GPIO_PIN_12 GPIO_BSRR_BS_12 /*!< Select pin 12 */ -#define LL_GPIO_PIN_13 GPIO_BSRR_BS_13 /*!< Select pin 13 */ -#define LL_GPIO_PIN_14 GPIO_BSRR_BS_14 /*!< Select pin 14 */ -#define LL_GPIO_PIN_15 GPIO_BSRR_BS_15 /*!< Select pin 15 */ -#define LL_GPIO_PIN_ALL (GPIO_BSRR_BS_0 | GPIO_BSRR_BS_1 | GPIO_BSRR_BS_2 | \ - GPIO_BSRR_BS_3 | GPIO_BSRR_BS_4 | GPIO_BSRR_BS_5 | \ - GPIO_BSRR_BS_6 | GPIO_BSRR_BS_7 | GPIO_BSRR_BS_8 | \ - GPIO_BSRR_BS_9 | GPIO_BSRR_BS_10 | GPIO_BSRR_BS_11 | \ - GPIO_BSRR_BS_12 | GPIO_BSRR_BS_13 | GPIO_BSRR_BS_14 | \ - GPIO_BSRR_BS_15) /*!< Select all pins */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_MODE Mode - * @{ - */ -#define LL_GPIO_MODE_INPUT (0x00000000U) /*!< Select input mode */ -#define LL_GPIO_MODE_OUTPUT GPIO_MODER_MODER0_0 /*!< Select output mode */ -#define LL_GPIO_MODE_ALTERNATE GPIO_MODER_MODER0_1 /*!< Select alternate function mode */ -#define LL_GPIO_MODE_ANALOG GPIO_MODER_MODER0 /*!< Select analog mode */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_OUTPUT Output Type - * @{ - */ -#define LL_GPIO_OUTPUT_PUSHPULL (0x00000000U) /*!< Select push-pull as output type */ -#define LL_GPIO_OUTPUT_OPENDRAIN GPIO_OTYPER_OT_0 /*!< Select open-drain as output type */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_SPEED Output Speed - * @{ - */ -#define LL_GPIO_SPEED_FREQ_LOW (0x00000000U) /*!< Select I/O low output speed */ -#define LL_GPIO_SPEED_FREQ_MEDIUM GPIO_OSPEEDER_OSPEEDR0_0 /*!< Select I/O medium output speed */ -#define LL_GPIO_SPEED_FREQ_HIGH GPIO_OSPEEDER_OSPEEDR0_1 /*!< Select I/O fast output speed */ -#define LL_GPIO_SPEED_FREQ_VERY_HIGH GPIO_OSPEEDER_OSPEEDR0 /*!< Select I/O high output speed */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_PULL Pull Up Pull Down - * @{ - */ -#define LL_GPIO_PULL_NO (0x00000000U) /*!< Select I/O no pull */ -#define LL_GPIO_PULL_UP GPIO_PUPDR_PUPDR0_0 /*!< Select I/O pull up */ -#define LL_GPIO_PULL_DOWN GPIO_PUPDR_PUPDR0_1 /*!< Select I/O pull down */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_AF Alternate Function - * @{ - */ -#define LL_GPIO_AF_0 (0x0000000U) /*!< Select alternate function 0 */ -#define LL_GPIO_AF_1 (0x0000001U) /*!< Select alternate function 1 */ -#define LL_GPIO_AF_2 (0x0000002U) /*!< Select alternate function 2 */ -#define LL_GPIO_AF_3 (0x0000003U) /*!< Select alternate function 3 */ -#define LL_GPIO_AF_4 (0x0000004U) /*!< Select alternate function 4 */ -#define LL_GPIO_AF_5 (0x0000005U) /*!< Select alternate function 5 */ -#define LL_GPIO_AF_6 (0x0000006U) /*!< Select alternate function 6 */ -#define LL_GPIO_AF_7 (0x0000007U) /*!< Select alternate function 7 */ -#define LL_GPIO_AF_8 (0x0000008U) /*!< Select alternate function 8 */ -#define LL_GPIO_AF_9 (0x0000009U) /*!< Select alternate function 9 */ -#define LL_GPIO_AF_10 (0x000000AU) /*!< Select alternate function 10 */ -#define LL_GPIO_AF_11 (0x000000BU) /*!< Select alternate function 11 */ -#define LL_GPIO_AF_12 (0x000000CU) /*!< Select alternate function 12 */ -#define LL_GPIO_AF_13 (0x000000DU) /*!< Select alternate function 13 */ -#define LL_GPIO_AF_14 (0x000000EU) /*!< Select alternate function 14 */ -#define LL_GPIO_AF_15 (0x000000FU) /*!< Select alternate function 15 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** @defgroup GPIO_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_GPIO_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_GPIO_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Functions GPIO Exported Functions - * @{ - */ - -/** @defgroup GPIO_LL_EF_Port_Configuration Port Configuration - * @{ - */ - -/** - * @brief Configure gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_SetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Mode) -{ - MODIFY_REG(GPIOx->MODER, (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U)), (Mode << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_GetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->MODER, - (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @rmtoll OTYPER OTy LL_GPIO_SetPinOutputType - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @param OutputType This parameter can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t PinMask, uint32_t OutputType) -{ - MODIFY_REG(GPIOx->OTYPER, PinMask, (PinMask * OutputType)); -} - -/** - * @brief Return gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll OTYPER OTy LL_GPIO_GetPinOutputType - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OTYPER, Pin) >> POSITION_VAL(Pin)); -} - -/** - * @brief Configure gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_SetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Speed This parameter can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Speed) -{ - MODIFY_REG(GPIOx->OSPEEDR, (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U)), - (Speed << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_GetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OSPEEDR, - (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio pull-up or pull-down for a dedicated pin on a dedicated port. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_SetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Pull This parameter can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Pull) -{ - MODIFY_REG(GPIOx->PUPDR, (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U)), (Pull << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio pull-up or pull-down for a dedicated pin on a dedicated port - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_GetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->PUPDR, - (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRL AFSELy LL_GPIO_SetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[0], (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U)), - (Alternate << (POSITION_VAL(Pin) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @rmtoll AFRL AFSELy LL_GPIO_GetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[0], - (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U))) >> (POSITION_VAL(Pin) * 4U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRH AFSELy LL_GPIO_SetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[1], (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U)), - (Alternate << (POSITION_VAL(Pin >> 8U) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @rmtoll AFRH AFSELy LL_GPIO_GetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[1], - (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U))) >> (POSITION_VAL(Pin >> 8U) * 4U)); -} - - -/** - * @brief Lock configuration of several pins for a dedicated port. - * @note When the lock sequence has been applied on a port bit, the - * value of this port bit can no longer be modified until the - * next reset. - * @note Each lock bit freezes a specific configuration register - * (control and alternate function registers). - * @rmtoll LCKR LCKK LL_GPIO_LockPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_LockPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - __IO uint32_t temp; - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - WRITE_REG(GPIOx->LCKR, PinMask); - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - temp = READ_REG(GPIOx->LCKR); - (void) temp; -} - -/** - * @brief Return 1 if all pins passed as parameter, of a dedicated port, are locked. else Return 0. - * @rmtoll LCKR LCKy LL_GPIO_IsPinLocked - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsPinLocked(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->LCKR, PinMask) == (PinMask)); -} - -/** - * @brief Return 1 if one of the pin of a dedicated port is locked. else return 0. - * @rmtoll LCKR LCKK LL_GPIO_IsAnyPinLocked - * @param GPIOx GPIO Port - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsAnyPinLocked(GPIO_TypeDef *GPIOx) -{ - return (READ_BIT(GPIOx->LCKR, GPIO_LCKR_LCKK) == (GPIO_LCKR_LCKK)); -} - -/** - * @} - */ - -/** @defgroup GPIO_LL_EF_Data_Access Data Access - * @{ - */ - -/** - * @brief Return full input data register value for a dedicated port. - * @rmtoll IDR IDy LL_GPIO_ReadInputPort - * @param GPIOx GPIO Port - * @retval Input data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadInputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->IDR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll IDR IDy LL_GPIO_IsInputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsInputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->IDR, PinMask) == (PinMask)); -} - -/** - * @brief Write output data register for the port. - * @rmtoll ODR ODy LL_GPIO_WriteOutputPort - * @param GPIOx GPIO Port - * @param PortValue Level value for each pin of the port - * @retval None - */ -__STATIC_INLINE void LL_GPIO_WriteOutputPort(GPIO_TypeDef *GPIOx, uint32_t PortValue) -{ - WRITE_REG(GPIOx->ODR, PortValue); -} - -/** - * @brief Return full output data register value for a dedicated port. - * @rmtoll ODR ODy LL_GPIO_ReadOutputPort - * @param GPIOx GPIO Port - * @retval Output data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadOutputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->ODR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll ODR ODy LL_GPIO_IsOutputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsOutputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->ODR, PinMask) == (PinMask)); -} - -/** - * @brief Set several pins to high level on dedicated gpio port. - * @rmtoll BSRR BSy LL_GPIO_SetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, PinMask); -} - -/** - * @brief Set several pins to low level on dedicated gpio port. - * @rmtoll BSRR BRy LL_GPIO_ResetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_ResetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, (PinMask << 16)); -} - -/** - * @brief Toggle data value for several pin of dedicated port. - * @rmtoll ODR ODy LL_GPIO_TogglePin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - uint32_t odr = READ_REG(GPIOx->ODR); - WRITE_REG(GPIOx->BSRR, ((odr & PinMask) << 16u) | (~odr & PinMask)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx); -ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct); -void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_GPIO_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_gpio.h + * @author MCD Application Team + * @brief Header file of GPIO LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_GPIO_H +#define __STM32F4xx_LL_GPIO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) + +/** @defgroup GPIO_LL GPIO + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup GPIO_LL_Private_Macros GPIO Private Macros + * @{ + */ + +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup GPIO_LL_ES_INIT GPIO Exported Init structures + * @{ + */ + +/** + * @brief LL GPIO Init Structure definition + */ +typedef struct +{ + uint32_t Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_LL_EC_PIN */ + + uint32_t Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIO_LL_EC_MODE. + + GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinMode().*/ + + uint32_t Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIO_LL_EC_SPEED. + + GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinSpeed().*/ + + uint32_t OutputType; /*!< Specifies the operating output type for the selected pins. + This parameter can be a value of @ref GPIO_LL_EC_OUTPUT. + + GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinOutputType().*/ + + uint32_t Pull; /*!< Specifies the operating Pull-up/Pull down for the selected pins. + This parameter can be a value of @ref GPIO_LL_EC_PULL. + + GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinPull().*/ + + uint32_t Alternate; /*!< Specifies the Peripheral to be connected to the selected pins. + This parameter can be a value of @ref GPIO_LL_EC_AF. + + GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetAFPin_0_7() and LL_GPIO_SetAFPin_8_15().*/ +} LL_GPIO_InitTypeDef; + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup GPIO_LL_Exported_Constants GPIO Exported Constants + * @{ + */ + +/** @defgroup GPIO_LL_EC_PIN PIN + * @{ + */ +#define LL_GPIO_PIN_0 GPIO_BSRR_BS_0 /*!< Select pin 0 */ +#define LL_GPIO_PIN_1 GPIO_BSRR_BS_1 /*!< Select pin 1 */ +#define LL_GPIO_PIN_2 GPIO_BSRR_BS_2 /*!< Select pin 2 */ +#define LL_GPIO_PIN_3 GPIO_BSRR_BS_3 /*!< Select pin 3 */ +#define LL_GPIO_PIN_4 GPIO_BSRR_BS_4 /*!< Select pin 4 */ +#define LL_GPIO_PIN_5 GPIO_BSRR_BS_5 /*!< Select pin 5 */ +#define LL_GPIO_PIN_6 GPIO_BSRR_BS_6 /*!< Select pin 6 */ +#define LL_GPIO_PIN_7 GPIO_BSRR_BS_7 /*!< Select pin 7 */ +#define LL_GPIO_PIN_8 GPIO_BSRR_BS_8 /*!< Select pin 8 */ +#define LL_GPIO_PIN_9 GPIO_BSRR_BS_9 /*!< Select pin 9 */ +#define LL_GPIO_PIN_10 GPIO_BSRR_BS_10 /*!< Select pin 10 */ +#define LL_GPIO_PIN_11 GPIO_BSRR_BS_11 /*!< Select pin 11 */ +#define LL_GPIO_PIN_12 GPIO_BSRR_BS_12 /*!< Select pin 12 */ +#define LL_GPIO_PIN_13 GPIO_BSRR_BS_13 /*!< Select pin 13 */ +#define LL_GPIO_PIN_14 GPIO_BSRR_BS_14 /*!< Select pin 14 */ +#define LL_GPIO_PIN_15 GPIO_BSRR_BS_15 /*!< Select pin 15 */ +#define LL_GPIO_PIN_ALL (GPIO_BSRR_BS_0 | GPIO_BSRR_BS_1 | GPIO_BSRR_BS_2 | \ + GPIO_BSRR_BS_3 | GPIO_BSRR_BS_4 | GPIO_BSRR_BS_5 | \ + GPIO_BSRR_BS_6 | GPIO_BSRR_BS_7 | GPIO_BSRR_BS_8 | \ + GPIO_BSRR_BS_9 | GPIO_BSRR_BS_10 | GPIO_BSRR_BS_11 | \ + GPIO_BSRR_BS_12 | GPIO_BSRR_BS_13 | GPIO_BSRR_BS_14 | \ + GPIO_BSRR_BS_15) /*!< Select all pins */ +/** + * @} + */ + +/** @defgroup GPIO_LL_EC_MODE Mode + * @{ + */ +#define LL_GPIO_MODE_INPUT (0x00000000U) /*!< Select input mode */ +#define LL_GPIO_MODE_OUTPUT GPIO_MODER_MODER0_0 /*!< Select output mode */ +#define LL_GPIO_MODE_ALTERNATE GPIO_MODER_MODER0_1 /*!< Select alternate function mode */ +#define LL_GPIO_MODE_ANALOG GPIO_MODER_MODER0 /*!< Select analog mode */ +/** + * @} + */ + +/** @defgroup GPIO_LL_EC_OUTPUT Output Type + * @{ + */ +#define LL_GPIO_OUTPUT_PUSHPULL (0x00000000U) /*!< Select push-pull as output type */ +#define LL_GPIO_OUTPUT_OPENDRAIN GPIO_OTYPER_OT_0 /*!< Select open-drain as output type */ +/** + * @} + */ + +/** @defgroup GPIO_LL_EC_SPEED Output Speed + * @{ + */ +#define LL_GPIO_SPEED_FREQ_LOW (0x00000000U) /*!< Select I/O low output speed */ +#define LL_GPIO_SPEED_FREQ_MEDIUM GPIO_OSPEEDER_OSPEEDR0_0 /*!< Select I/O medium output speed */ +#define LL_GPIO_SPEED_FREQ_HIGH GPIO_OSPEEDER_OSPEEDR0_1 /*!< Select I/O fast output speed */ +#define LL_GPIO_SPEED_FREQ_VERY_HIGH GPIO_OSPEEDER_OSPEEDR0 /*!< Select I/O high output speed */ +/** + * @} + */ + +/** @defgroup GPIO_LL_EC_PULL Pull Up Pull Down + * @{ + */ +#define LL_GPIO_PULL_NO (0x00000000U) /*!< Select I/O no pull */ +#define LL_GPIO_PULL_UP GPIO_PUPDR_PUPDR0_0 /*!< Select I/O pull up */ +#define LL_GPIO_PULL_DOWN GPIO_PUPDR_PUPDR0_1 /*!< Select I/O pull down */ +/** + * @} + */ + +/** @defgroup GPIO_LL_EC_AF Alternate Function + * @{ + */ +#define LL_GPIO_AF_0 (0x0000000U) /*!< Select alternate function 0 */ +#define LL_GPIO_AF_1 (0x0000001U) /*!< Select alternate function 1 */ +#define LL_GPIO_AF_2 (0x0000002U) /*!< Select alternate function 2 */ +#define LL_GPIO_AF_3 (0x0000003U) /*!< Select alternate function 3 */ +#define LL_GPIO_AF_4 (0x0000004U) /*!< Select alternate function 4 */ +#define LL_GPIO_AF_5 (0x0000005U) /*!< Select alternate function 5 */ +#define LL_GPIO_AF_6 (0x0000006U) /*!< Select alternate function 6 */ +#define LL_GPIO_AF_7 (0x0000007U) /*!< Select alternate function 7 */ +#define LL_GPIO_AF_8 (0x0000008U) /*!< Select alternate function 8 */ +#define LL_GPIO_AF_9 (0x0000009U) /*!< Select alternate function 9 */ +#define LL_GPIO_AF_10 (0x000000AU) /*!< Select alternate function 10 */ +#define LL_GPIO_AF_11 (0x000000BU) /*!< Select alternate function 11 */ +#define LL_GPIO_AF_12 (0x000000CU) /*!< Select alternate function 12 */ +#define LL_GPIO_AF_13 (0x000000DU) /*!< Select alternate function 13 */ +#define LL_GPIO_AF_14 (0x000000EU) /*!< Select alternate function 14 */ +#define LL_GPIO_AF_15 (0x000000FU) /*!< Select alternate function 15 */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup GPIO_LL_Exported_Macros GPIO Exported Macros + * @{ + */ + +/** @defgroup GPIO_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in GPIO register + * @param __INSTANCE__ GPIO Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_GPIO_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in GPIO register + * @param __INSTANCE__ GPIO Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_GPIO_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup GPIO_LL_Exported_Functions GPIO Exported Functions + * @{ + */ + +/** @defgroup GPIO_LL_EF_Port_Configuration Port Configuration + * @{ + */ + +/** + * @brief Configure gpio mode for a dedicated pin on dedicated port. + * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll MODER MODEy LL_GPIO_SetPinMode + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @param Mode This parameter can be one of the following values: + * @arg @ref LL_GPIO_MODE_INPUT + * @arg @ref LL_GPIO_MODE_OUTPUT + * @arg @ref LL_GPIO_MODE_ALTERNATE + * @arg @ref LL_GPIO_MODE_ANALOG + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Mode) +{ + MODIFY_REG(GPIOx->MODER, (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U)), (Mode << (POSITION_VAL(Pin) * 2U))); +} + +/** + * @brief Return gpio mode for a dedicated pin on dedicated port. + * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll MODER MODEy LL_GPIO_GetPinMode + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_MODE_INPUT + * @arg @ref LL_GPIO_MODE_OUTPUT + * @arg @ref LL_GPIO_MODE_ALTERNATE + * @arg @ref LL_GPIO_MODE_ANALOG + */ +__STATIC_INLINE uint32_t LL_GPIO_GetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->MODER, + (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); +} + +/** + * @brief Configure gpio output type for several pins on dedicated port. + * @note Output type as to be set when gpio pin is in output or + * alternate modes. Possible type are Push-pull or Open-drain. + * @rmtoll OTYPER OTy LL_GPIO_SetPinOutputType + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @param OutputType This parameter can be one of the following values: + * @arg @ref LL_GPIO_OUTPUT_PUSHPULL + * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t PinMask, uint32_t OutputType) +{ + MODIFY_REG(GPIOx->OTYPER, PinMask, (PinMask * OutputType)); +} + +/** + * @brief Return gpio output type for several pins on dedicated port. + * @note Output type as to be set when gpio pin is in output or + * alternate modes. Possible type are Push-pull or Open-drain. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll OTYPER OTy LL_GPIO_GetPinOutputType + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_OUTPUT_PUSHPULL + * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN + */ +__STATIC_INLINE uint32_t LL_GPIO_GetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->OTYPER, Pin) >> POSITION_VAL(Pin)); +} + +/** + * @brief Configure gpio speed for a dedicated pin on dedicated port. + * @note I/O speed can be Low, Medium, Fast or High speed. + * @note Warning: only one pin can be passed as parameter. + * @note Refer to datasheet for frequency specifications and the power + * supply and load conditions for each speed. + * @rmtoll OSPEEDR OSPEEDy LL_GPIO_SetPinSpeed + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @param Speed This parameter can be one of the following values: + * @arg @ref LL_GPIO_SPEED_FREQ_LOW + * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM + * @arg @ref LL_GPIO_SPEED_FREQ_HIGH + * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Speed) +{ + MODIFY_REG(GPIOx->OSPEEDR, (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U)), + (Speed << (POSITION_VAL(Pin) * 2U))); +} + +/** + * @brief Return gpio speed for a dedicated pin on dedicated port. + * @note I/O speed can be Low, Medium, Fast or High speed. + * @note Warning: only one pin can be passed as parameter. + * @note Refer to datasheet for frequency specifications and the power + * supply and load conditions for each speed. + * @rmtoll OSPEEDR OSPEEDy LL_GPIO_GetPinSpeed + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_SPEED_FREQ_LOW + * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM + * @arg @ref LL_GPIO_SPEED_FREQ_HIGH + * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH + */ +__STATIC_INLINE uint32_t LL_GPIO_GetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->OSPEEDR, + (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); +} + +/** + * @brief Configure gpio pull-up or pull-down for a dedicated pin on a dedicated port. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll PUPDR PUPDy LL_GPIO_SetPinPull + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @param Pull This parameter can be one of the following values: + * @arg @ref LL_GPIO_PULL_NO + * @arg @ref LL_GPIO_PULL_UP + * @arg @ref LL_GPIO_PULL_DOWN + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Pull) +{ + MODIFY_REG(GPIOx->PUPDR, (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U)), (Pull << (POSITION_VAL(Pin) * 2U))); +} + +/** + * @brief Return gpio pull-up or pull-down for a dedicated pin on a dedicated port + * @note Warning: only one pin can be passed as parameter. + * @rmtoll PUPDR PUPDy LL_GPIO_GetPinPull + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_PULL_NO + * @arg @ref LL_GPIO_PULL_UP + * @arg @ref LL_GPIO_PULL_DOWN + */ +__STATIC_INLINE uint32_t LL_GPIO_GetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->PUPDR, + (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); +} + +/** + * @brief Configure gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. + * @note Possible values are from AF0 to AF15 depending on target. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll AFRL AFSELy LL_GPIO_SetAFPin_0_7 + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @param Alternate This parameter can be one of the following values: + * @arg @ref LL_GPIO_AF_0 + * @arg @ref LL_GPIO_AF_1 + * @arg @ref LL_GPIO_AF_2 + * @arg @ref LL_GPIO_AF_3 + * @arg @ref LL_GPIO_AF_4 + * @arg @ref LL_GPIO_AF_5 + * @arg @ref LL_GPIO_AF_6 + * @arg @ref LL_GPIO_AF_7 + * @arg @ref LL_GPIO_AF_8 + * @arg @ref LL_GPIO_AF_9 + * @arg @ref LL_GPIO_AF_10 + * @arg @ref LL_GPIO_AF_11 + * @arg @ref LL_GPIO_AF_12 + * @arg @ref LL_GPIO_AF_13 + * @arg @ref LL_GPIO_AF_14 + * @arg @ref LL_GPIO_AF_15 + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) +{ + MODIFY_REG(GPIOx->AFR[0], (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U)), + (Alternate << (POSITION_VAL(Pin) * 4U))); +} + +/** + * @brief Return gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. + * @rmtoll AFRL AFSELy LL_GPIO_GetAFPin_0_7 + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_AF_0 + * @arg @ref LL_GPIO_AF_1 + * @arg @ref LL_GPIO_AF_2 + * @arg @ref LL_GPIO_AF_3 + * @arg @ref LL_GPIO_AF_4 + * @arg @ref LL_GPIO_AF_5 + * @arg @ref LL_GPIO_AF_6 + * @arg @ref LL_GPIO_AF_7 + * @arg @ref LL_GPIO_AF_8 + * @arg @ref LL_GPIO_AF_9 + * @arg @ref LL_GPIO_AF_10 + * @arg @ref LL_GPIO_AF_11 + * @arg @ref LL_GPIO_AF_12 + * @arg @ref LL_GPIO_AF_13 + * @arg @ref LL_GPIO_AF_14 + * @arg @ref LL_GPIO_AF_15 + */ +__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->AFR[0], + (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U))) >> (POSITION_VAL(Pin) * 4U)); +} + +/** + * @brief Configure gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. + * @note Possible values are from AF0 to AF15 depending on target. + * @note Warning: only one pin can be passed as parameter. + * @rmtoll AFRH AFSELy LL_GPIO_SetAFPin_8_15 + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @param Alternate This parameter can be one of the following values: + * @arg @ref LL_GPIO_AF_0 + * @arg @ref LL_GPIO_AF_1 + * @arg @ref LL_GPIO_AF_2 + * @arg @ref LL_GPIO_AF_3 + * @arg @ref LL_GPIO_AF_4 + * @arg @ref LL_GPIO_AF_5 + * @arg @ref LL_GPIO_AF_6 + * @arg @ref LL_GPIO_AF_7 + * @arg @ref LL_GPIO_AF_8 + * @arg @ref LL_GPIO_AF_9 + * @arg @ref LL_GPIO_AF_10 + * @arg @ref LL_GPIO_AF_11 + * @arg @ref LL_GPIO_AF_12 + * @arg @ref LL_GPIO_AF_13 + * @arg @ref LL_GPIO_AF_14 + * @arg @ref LL_GPIO_AF_15 + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) +{ + MODIFY_REG(GPIOx->AFR[1], (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U)), + (Alternate << (POSITION_VAL(Pin >> 8U) * 4U))); +} + +/** + * @brief Return gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. + * @note Possible values are from AF0 to AF15 depending on target. + * @rmtoll AFRH AFSELy LL_GPIO_GetAFPin_8_15 + * @param GPIOx GPIO Port + * @param Pin This parameter can be one of the following values: + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @retval Returned value can be one of the following values: + * @arg @ref LL_GPIO_AF_0 + * @arg @ref LL_GPIO_AF_1 + * @arg @ref LL_GPIO_AF_2 + * @arg @ref LL_GPIO_AF_3 + * @arg @ref LL_GPIO_AF_4 + * @arg @ref LL_GPIO_AF_5 + * @arg @ref LL_GPIO_AF_6 + * @arg @ref LL_GPIO_AF_7 + * @arg @ref LL_GPIO_AF_8 + * @arg @ref LL_GPIO_AF_9 + * @arg @ref LL_GPIO_AF_10 + * @arg @ref LL_GPIO_AF_11 + * @arg @ref LL_GPIO_AF_12 + * @arg @ref LL_GPIO_AF_13 + * @arg @ref LL_GPIO_AF_14 + * @arg @ref LL_GPIO_AF_15 + */ +__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin) +{ + return (uint32_t)(READ_BIT(GPIOx->AFR[1], + (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U))) >> (POSITION_VAL(Pin >> 8U) * 4U)); +} + + +/** + * @brief Lock configuration of several pins for a dedicated port. + * @note When the lock sequence has been applied on a port bit, the + * value of this port bit can no longer be modified until the + * next reset. + * @note Each lock bit freezes a specific configuration register + * (control and alternate function registers). + * @rmtoll LCKR LCKK LL_GPIO_LockPin + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval None + */ +__STATIC_INLINE void LL_GPIO_LockPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + __IO uint32_t temp; + WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); + WRITE_REG(GPIOx->LCKR, PinMask); + WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); + temp = READ_REG(GPIOx->LCKR); + (void) temp; +} + +/** + * @brief Return 1 if all pins passed as parameter, of a dedicated port, are locked. else Return 0. + * @rmtoll LCKR LCKy LL_GPIO_IsPinLocked + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_GPIO_IsPinLocked(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + return (READ_BIT(GPIOx->LCKR, PinMask) == (PinMask)); +} + +/** + * @brief Return 1 if one of the pin of a dedicated port is locked. else return 0. + * @rmtoll LCKR LCKK LL_GPIO_IsAnyPinLocked + * @param GPIOx GPIO Port + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_GPIO_IsAnyPinLocked(GPIO_TypeDef *GPIOx) +{ + return (READ_BIT(GPIOx->LCKR, GPIO_LCKR_LCKK) == (GPIO_LCKR_LCKK)); +} + +/** + * @} + */ + +/** @defgroup GPIO_LL_EF_Data_Access Data Access + * @{ + */ + +/** + * @brief Return full input data register value for a dedicated port. + * @rmtoll IDR IDy LL_GPIO_ReadInputPort + * @param GPIOx GPIO Port + * @retval Input data register value of port + */ +__STATIC_INLINE uint32_t LL_GPIO_ReadInputPort(GPIO_TypeDef *GPIOx) +{ + return (uint32_t)(READ_REG(GPIOx->IDR)); +} + +/** + * @brief Return if input data level for several pins of dedicated port is high or low. + * @rmtoll IDR IDy LL_GPIO_IsInputPinSet + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_GPIO_IsInputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + return (READ_BIT(GPIOx->IDR, PinMask) == (PinMask)); +} + +/** + * @brief Write output data register for the port. + * @rmtoll ODR ODy LL_GPIO_WriteOutputPort + * @param GPIOx GPIO Port + * @param PortValue Level value for each pin of the port + * @retval None + */ +__STATIC_INLINE void LL_GPIO_WriteOutputPort(GPIO_TypeDef *GPIOx, uint32_t PortValue) +{ + WRITE_REG(GPIOx->ODR, PortValue); +} + +/** + * @brief Return full output data register value for a dedicated port. + * @rmtoll ODR ODy LL_GPIO_ReadOutputPort + * @param GPIOx GPIO Port + * @retval Output data register value of port + */ +__STATIC_INLINE uint32_t LL_GPIO_ReadOutputPort(GPIO_TypeDef *GPIOx) +{ + return (uint32_t)(READ_REG(GPIOx->ODR)); +} + +/** + * @brief Return if input data level for several pins of dedicated port is high or low. + * @rmtoll ODR ODy LL_GPIO_IsOutputPinSet + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_GPIO_IsOutputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + return (READ_BIT(GPIOx->ODR, PinMask) == (PinMask)); +} + +/** + * @brief Set several pins to high level on dedicated gpio port. + * @rmtoll BSRR BSy LL_GPIO_SetOutputPin + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval None + */ +__STATIC_INLINE void LL_GPIO_SetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + WRITE_REG(GPIOx->BSRR, PinMask); +} + +/** + * @brief Set several pins to low level on dedicated gpio port. + * @rmtoll BSRR BRy LL_GPIO_ResetOutputPin + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval None + */ +__STATIC_INLINE void LL_GPIO_ResetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + WRITE_REG(GPIOx->BSRR, (PinMask << 16)); +} + +/** + * @brief Toggle data value for several pin of dedicated port. + * @rmtoll ODR ODy LL_GPIO_TogglePin + * @param GPIOx GPIO Port + * @param PinMask This parameter can be a combination of the following values: + * @arg @ref LL_GPIO_PIN_0 + * @arg @ref LL_GPIO_PIN_1 + * @arg @ref LL_GPIO_PIN_2 + * @arg @ref LL_GPIO_PIN_3 + * @arg @ref LL_GPIO_PIN_4 + * @arg @ref LL_GPIO_PIN_5 + * @arg @ref LL_GPIO_PIN_6 + * @arg @ref LL_GPIO_PIN_7 + * @arg @ref LL_GPIO_PIN_8 + * @arg @ref LL_GPIO_PIN_9 + * @arg @ref LL_GPIO_PIN_10 + * @arg @ref LL_GPIO_PIN_11 + * @arg @ref LL_GPIO_PIN_12 + * @arg @ref LL_GPIO_PIN_13 + * @arg @ref LL_GPIO_PIN_14 + * @arg @ref LL_GPIO_PIN_15 + * @arg @ref LL_GPIO_PIN_ALL + * @retval None + */ +__STATIC_INLINE void LL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint32_t PinMask) +{ + uint32_t odr = READ_REG(GPIOx->ODR); + WRITE_REG(GPIOx->BSRR, ((odr & PinMask) << 16u) | (~odr & PinMask)); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup GPIO_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx); +ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct); +void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct); + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_GPIO_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h index babba6b..2ef20f7 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h @@ -1,1890 +1,1890 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_i2c.h - * @author MCD Application Team - * @brief Header file of I2C LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_I2C_H -#define __STM32F4xx_LL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (I2C1) || defined (I2C2) || defined (I2C3) - -/** @defgroup I2C_LL I2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_LL_Private_Constants I2C Private Constants - * @{ - */ - -/* Defines used to perform compute and check in the macros */ -#define LL_I2C_MAX_SPEED_STANDARD 100000U -#define LL_I2C_MAX_SPEED_FAST 400000U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_Private_Macros I2C Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_ES_INIT I2C Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeripheralMode; /*!< Specifies the peripheral mode. - This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetMode(). */ - - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz (in Hz) - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetClockPeriod() - or @ref LL_I2C_SetDutyCycle() or @ref LL_I2C_SetClockSpeedMode() or @ref LL_I2C_ConfigSpeed(). */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_LL_EC_DUTYCYCLE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDutyCycle(). */ - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. - This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION - - This feature can be modified afterwards using unitary functions @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */ - - uint32_t DigitalFilter; /*!< Configures the digital noise filter. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDigitalFilter(). */ - -#endif - uint32_t OwnAddress1; /*!< Specifies the device own address 1. - This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ - - uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE - - This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */ - - uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). - This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1 - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ -} LL_I2C_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_I2C_ReadReg function - * @{ - */ -#define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */ -#define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or - Address matched flag (slave mode) */ -#define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */ -#define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */ -#define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */ -#define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */ -#define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */ -#define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */ -#define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */ -#define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */ -#define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */ -#define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ -#define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ -#define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */ -#define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */ -#define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */ -#define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */ -#define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */ -#define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */ -#define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */ -#define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions - * @{ - */ -#define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */ -#define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */ -#define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */ -/** - * @} - */ - -#if defined(I2C_FLTR_ANOFF) -/** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection - * @{ - */ -#define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ -#define LL_I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF /*!< Analog filter is disabled.*/ -/** - * @} - */ - -#endif -/** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length - * @{ - */ -#define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */ -#define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle - * @{ - */ -#define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */ -#define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode - * @{ - */ -#define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */ -#define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode - * @{ - */ -#define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */ -#define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */ -#define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */ -#define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation - * @{ - */ -#define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */ -#define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DIRECTION Read Write Direction - * @{ - */ -#define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */ -#define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Convert Peripheral Clock Frequency in Mhz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @retval Value of peripheral clock (in Mhz) - */ -#define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U) - -/** - * @brief Convert Peripheral Clock Frequency in Hz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz). - * @retval Value of peripheral clock (in Hz) - */ -#define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U) - -/** - * @brief Compute I2C Clock rising time. - * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -#define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) - -/** - * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -#define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \ - (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \ - (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__)))) - -/** - * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz). - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF. - */ -#define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) - -/** - * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x001 and Max_Data=0xFFF - */ -#define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \ - (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \ - (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U)))) - -/** - * @brief Get the Least significant bits of a 10-Bits address. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -#define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Write direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF0 and Max_Data=0xF6 - */ -#define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Read direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF1 and Max_Data=0xF7 - */ -#define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1)))) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2C_LL_Exported_Functions I2C Exported Functions - * @{ - */ - -/** @defgroup I2C_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable I2C peripheral (PE = 1). - * @rmtoll CR1 PE LL_I2C_Enable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Disable I2C peripheral (PE = 0). - * @rmtoll CR1 PE LL_I2C_Disable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Check if the I2C peripheral is enabled or disabled. - * @rmtoll CR1 PE LL_I2C_IsEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE)); -} - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/** - * @brief Configure Noise Filters (Analog and Digital). - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * The filters can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_ConfigFilters\n - * FLTR DNF LL_I2C_ConfigFilters - * @param I2Cx I2C Instance. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref LL_I2C_ANALOGFILTER_ENABLE - * @arg @ref LL_I2C_ANALOGFILTER_DISABLE - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_ANOFF | I2C_FLTR_DNF, AnalogFilter | DigitalFilter); -} -#endif -#if defined(I2C_FLTR_DNF) - -/** - * @brief Configure Digital Noise Filter. - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR DNF LL_I2C_SetDigitalFilter - * @param I2Cx I2C Instance. - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_DNF, DigitalFilter); -} - -/** - * @brief Get the current Digital Noise Filter configuration. - * @rmtoll FLTR DNF LL_I2C_GetDigitalFilter - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->FLTR, I2C_FLTR_DNF)); -} -#endif -#if defined(I2C_FLTR_ANOFF) - -/** - * @brief Enable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_EnableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Disable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_DisableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Check if Analog Noise Filter is enabled or disabled. - * @rmtoll FLTR ANOFF LL_I2C_IsEnabledAnalogFilter - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF) == (I2C_FLTR_ANOFF)); -} -#endif - -/** - * @brief Enable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA transmission requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Enable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA reception requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Get the data register address used for DMA transfer. - * @rmtoll DR DR LL_I2C_DMA_GetRegAddr - * @param I2Cx I2C Instance. - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef *I2Cx) -{ - return (uint32_t) & (I2Cx->DR); -} - -/** - * @brief Enable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Disable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Check if Clock stretching is enabled or disabled. - * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH)); -} - -/** - * @brief Enable General Call. - * @note When enabled the Address 0x00 is ACKed. - * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Disable General Call. - * @note When disabled the Address 0x00 is NACKed. - * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Check if General Call is enabled or disabled. - * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENGC) == (I2C_CR1_ENGC)); -} - -/** - * @brief Set the Own Address1. - * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n - * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n - * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n - * OAR1 ADDMODE LL_I2C_SetOwnAddress1 - * @param I2Cx I2C Instance. - * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. - * @param OwnAddrSize This parameter can be one of the following values: - * @arg @ref LL_I2C_OWNADDRESS1_7BIT - * @arg @ref LL_I2C_OWNADDRESS1_10BIT - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) -{ - MODIFY_REG(I2Cx->OAR1, I2C_OAR1_ADD0 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD8_9 | I2C_OAR1_ADDMODE, OwnAddress1 | OwnAddrSize); -} - -/** - * @brief Set the 7bits Own Address2. - * @note This action has no effect if own address2 is enabled. - * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2 - * @param I2Cx I2C Instance. - * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2) -{ - MODIFY_REG(I2Cx->OAR2, I2C_OAR2_ADD2, OwnAddress2); -} - -/** - * @brief Enable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Disable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL) == (I2C_OAR2_ENDUAL)); -} - -/** - * @brief Configure the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetPeriphClock(I2C_TypeDef *I2Cx, uint32_t PeriphClock) -{ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock)); -} - -/** - * @brief Get the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock - * @param I2Cx I2C Instance. - * @retval Value of Peripheral Clock (in Hz) - */ -__STATIC_INLINE uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx->CR2, I2C_CR2_FREQ))); -} - -/** - * @brief Configure the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_SetDutyCycle - * @param I2Cx I2C Instance. - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDutyCycle(I2C_TypeDef *I2Cx, uint32_t DutyCycle) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_DUTY, DutyCycle); -} - -/** - * @brief Get the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_GetDutyCycle - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - */ -__STATIC_INLINE uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_DUTY)); -} - -/** - * @brief Configure the I2C master clock speed mode. - * @rmtoll CCR FS LL_I2C_SetClockSpeedMode - * @param I2Cx I2C Instance. - * @param ClockSpeedMode This parameter can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockSpeedMode(I2C_TypeDef *I2Cx, uint32_t ClockSpeedMode) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_FS, ClockSpeedMode); -} - -/** - * @brief Get the the I2C master speed mode. - * @rmtoll CCR FS LL_I2C_GetClockSpeedMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_FS)); -} - -/** - * @brief Configure the SCL, SDA rising time. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll TRISE TRISE LL_I2C_SetRiseTime - * @param I2Cx I2C Instance. - * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetRiseTime(I2C_TypeDef *I2Cx, uint32_t RiseTime) -{ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, RiseTime); -} - -/** - * @brief Get the SCL, SDA rising time. - * @rmtoll TRISE TRISE LL_I2C_GetRiseTime - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_I2C_GetRiseTime(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->TRISE, I2C_TRISE_TRISE)); -} - -/** - * @brief Configure the SCL high and low period. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CCR CCR LL_I2C_SetClockPeriod - * @param I2Cx I2C Instance. - * @param ClockPeriod This parameter must be a value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockPeriod(I2C_TypeDef *I2Cx, uint32_t ClockPeriod) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_CCR, ClockPeriod); -} - -/** - * @brief Get the SCL high and low period. - * @rmtoll CCR CCR LL_I2C_GetClockPeriod - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_CCR)); -} - -/** - * @brief Configure the SCL speed. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n - * TRISE TRISE LL_I2C_ConfigSpeed\n - * CCR FS LL_I2C_ConfigSpeed\n - * CCR DUTY LL_I2C_ConfigSpeed\n - * CCR CCR LL_I2C_ConfigSpeed - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz). - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigSpeed(I2C_TypeDef *I2Cx, uint32_t PeriphClock, uint32_t ClockSpeed, - uint32_t DutyCycle) -{ - uint32_t freqrange = 0x0U; - uint32_t clockconfig = 0x0U; - - /* Compute frequency range */ - freqrange = __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock); - - /* Configure I2Cx: Frequency range register */ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, freqrange); - - /* Configure I2Cx: Rise Time register */ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, __LL_I2C_RISE_TIME(freqrange, ClockSpeed)); - - /* Configure Speed mode, Duty Cycle and Clock control register value */ - if (ClockSpeed > LL_I2C_MAX_SPEED_STANDARD) - { - /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_FAST_MODE | \ - __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock, ClockSpeed, DutyCycle) | \ - DutyCycle; - } - else - { - /* Set Speed mode at standard for Clock Speed request in standard clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_STANDARD_MODE | \ - __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock, ClockSpeed); - } - - /* Configure I2Cx: Clock control register */ - MODIFY_REG(I2Cx->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), clockconfig); -} - -/** - * @brief Configure peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_SetMode\n - * CR1 SMBTYPE LL_I2C_SetMode\n - * CR1 ENARP LL_I2C_SetMode - * @param I2Cx I2C Instance. - * @param PeripheralMode This parameter can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP, PeripheralMode); -} - -/** - * @brief Get peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_GetMode\n - * CR1 SMBTYPE LL_I2C_GetMode\n - * CR1 ENARP LL_I2C_GetMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - */ -__STATIC_INLINE uint32_t LL_I2C_GetMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP)); -} - -/** - * @brief Enable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is drived low and - * Alert Response Address Header acknowledge is enabled. - * SMBus Host mode: - * - SMBus Alert pin management is supported. - * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Disable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is not drived (can be used as a standard GPIO) and - * Alert Response Address Header acknowledge is disabled. - * SMBus Host mode: - * - SMBus Alert pin management is not supported. - * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ALERT) == (I2C_CR1_ALERT)); -} - -/** - * @brief Enable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Disable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENPEC) == (I2C_CR1_ENPEC)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n - * CR2 ITBUFEN LL_I2C_EnableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n - * CR2 ITBUFEN LL_I2C_DisableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the TXE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n - * CR2 ITBUFEN LL_I2C_EnableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n - * CR2 ITBUFEN LL_I2C_DisableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the RXNE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * - * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_EVT(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Disable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_EVT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Check if Events interrupts are enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN) == (I2C_CR2_ITEVTEN)); -} - -/** - * @brief Enable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_BUF(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_BUF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if Buffer interrupts are enabled or disabled. - * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN) == (I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Disable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Check if Error interrupts are enabled or disabled. - * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITERREN) == (I2C_CR2_ITERREN)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_FLAG_management FLAG_management - * @{ - */ - -/** - * @brief Indicate the status of Transmit data register empty flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TXE) == (I2C_SR1_TXE)); -} - -/** - * @brief Indicate the status of Byte Transfer Finished flag. - * RESET: When Data byte transfer not done. - * SET: When Data byte transfer succeeded. - * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BTF) == (I2C_SR1_BTF)); -} - -/** - * @brief Indicate the status of Receive data register not empty flag. - * @note RESET: When Receive data register is read. - * SET: When the received data is copied in Receive data register. - * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_RXNE) == (I2C_SR1_RXNE)); -} - -/** - * @brief Indicate the status of Start Bit (master mode). - * @note RESET: When No Start condition. - * SET: When Start condition is generated. - * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SB) == (I2C_SR1_SB)); -} - -/** - * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode). - * @note RESET: Clear default value. - * SET: When the address is fully sent (master mode) or when the received slave address matched with one of the enabled slave address (slave mode). - * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADDR) == (I2C_SR1_ADDR)); -} - -/** - * @brief Indicate the status of 10-bit header sent (master mode). - * @note RESET: When no ADD10 event occurred. - * SET: When the master has sent the first address byte (header). - * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADD10) == (I2C_SR1_ADD10)); -} - -/** - * @brief Indicate the status of Acknowledge failure flag. - * @note RESET: No acknowledge failure. - * SET: When an acknowledge failure is received after a byte transmission. - * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_AF) == (I2C_SR1_AF)); -} - -/** - * @brief Indicate the status of Stop detection flag (slave mode). - * @note RESET: Clear default value. - * SET: When a Stop condition is detected. - * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_STOPF) == (I2C_SR1_STOPF)); -} - -/** - * @brief Indicate the status of Bus error flag. - * @note RESET: Clear default value. - * SET: When a misplaced Start or Stop condition is detected. - * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BERR) == (I2C_SR1_BERR)); -} - -/** - * @brief Indicate the status of Arbitration lost flag. - * @note RESET: Clear default value. - * SET: When arbitration lost. - * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ARLO) == (I2C_SR1_ARLO)); -} - -/** - * @brief Indicate the status of Overrun/Underrun flag. - * @note RESET: Clear default value. - * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). - * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_OVR) == (I2C_SR1_OVR)); -} - -/** - * @brief Indicate the status of SMBus PEC error flag in reception. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_PECERR) == (I2C_SR1_PECERR)); -} - -/** - * @brief Indicate the status of SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT) == (I2C_SR1_TIMEOUT)); -} - -/** - * @brief Indicate the status of SMBus alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SMBALERT) == (I2C_SR1_SMBALERT)); -} - -/** - * @brief Indicate the status of Bus Busy flag. - * @note RESET: Clear default value. - * SET: When a Start condition is detected. - * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_BUSY) == (I2C_SR2_BUSY)); -} - -/** - * @brief Indicate the status of Dual flag. - * @note RESET: Received address matched with OAR1. - * SET: Received address matched with OAR2. - * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_DUALF) == (I2C_SR2_DUALF)); -} - -/** - * @brief Indicate the status of SMBus Host address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Host address - * SET: SMBus Host address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBHOST) == (I2C_SR2_SMBHOST)); -} - -/** - * @brief Indicate the status of SMBus Device default address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Device default address - * SET: SMBus Device default address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBDEFAULT) == (I2C_SR2_SMBDEFAULT)); -} - -/** - * @brief Indicate the status of General call address reception (Slave mode). - * @note RESET: No General call address - * SET: General call address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_GENCALL) == (I2C_SR2_GENCALL)); -} - -/** - * @brief Indicate the status of Master/Slave flag. - * @note RESET: Slave Mode. - * SET: Master Mode. - * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_MSL) == (I2C_SR2_MSL)); -} - -/** - * @brief Clear Address Matched flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a read access to the I2Cx_SR2 register. - * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - tmpreg = I2Cx->SR2; - (void) tmpreg; -} - -/** - * @brief Clear Acknowledge failure flag. - * @rmtoll SR1 AF LL_I2C_ClearFlag_AF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_AF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_AF); -} - -/** - * @brief Clear Stop detection flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a write access to I2Cx_CR1 register. - * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n - * CR1 PE LL_I2C_ClearFlag_STOP - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Clear Bus error flag. - * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_BERR); -} - -/** - * @brief Clear Arbitration lost flag. - * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_ARLO); -} - -/** - * @brief Clear Overrun/Underrun flag. - * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_OVR); -} - -/** - * @brief Clear SMBus PEC error flag. - * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_PECERR); -} - -/** - * @brief Clear SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT); -} - -/** - * @brief Clear SMBus Alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_SMBALERT); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Enable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_EnableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableReset(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Disable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_DisableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableReset(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Check if the I2C peripheral is under reset state or not. - * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_SWRST) == (I2C_CR1_SWRST)); -} - -/** - * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - * @note Usage in Slave or Master mode. - * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData - * @param I2Cx I2C Instance. - * @param TypeAcknowledge This parameter can be one of the following values: - * @arg @ref LL_I2C_ACK - * @arg @ref LL_I2C_NACK - * @retval None - */ -__STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_ACK, TypeAcknowledge); -} - -/** - * @brief Generate a START or RESTART condition - * @note The START bit can be set even if bus is BUSY or I2C is in slave mode. - * This action has no effect when RELOAD is set. - * @rmtoll CR1 START LL_I2C_GenerateStartCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_START); -} - -/** - * @brief Generate a STOP condition after the current byte transfer (master mode). - * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_STOP); -} - -/** - * @brief Enable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the next byte received or the PEC bit indicates that the next byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_EnableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableBitPOS(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Disable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the current byte received or the PEC bit indicates that the current byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_DisableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableBitPOS(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Check if bit POS is enabled or disabled. - * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_POS) == (I2C_CR1_POS)); -} - -/** - * @brief Indicate the value of transfer direction. - * @note RESET: Bus is in read transfer (peripheral point of view). - * SET: Bus is in write transfer (peripheral point of view). - * @rmtoll SR2 TRA LL_I2C_GetTransferDirection - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DIRECTION_WRITE - * @arg @ref LL_I2C_DIRECTION_READ - */ -__STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_TRA)); -} - -/** - * @brief Enable DMA last transfer. - * @note This action mean that next DMA EOT is the last transfer. - * @rmtoll CR2 LAST LL_I2C_EnableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableLastDMA(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Disable DMA last transfer. - * @note This action mean that next DMA EOT is not the last transfer. - * @rmtoll CR2 LAST LL_I2C_DisableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableLastDMA(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Check if DMA last transfer is enabled or disabled. - * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_LAST) == (I2C_CR2_LAST)); -} - -/** - * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note This feature is cleared by hardware when the PEC byte is transferred or compared, - * or by a START or STOP condition, it is also cleared by software. - * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PEC) == (I2C_CR1_PEC)); -} - -/** - * @brief Get the SMBus Packet Error byte calculated. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_PEC) >> I2C_SR2_PEC_Pos); -} - -/** - * @brief Read Receive Data register. - * @rmtoll DR DR LL_I2C_ReceiveData8 - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_I2C_ReceiveData8(I2C_TypeDef *I2Cx) -{ - return (uint8_t)(READ_BIT(I2Cx->DR, I2C_DR_DR)); -} - -/** - * @brief Write in Transmit Data Register . - * @rmtoll DR DR LL_I2C_TransmitData8 - * @param I2Cx I2C Instance. - * @param Data Value between Min_Data=0x0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data) -{ - MODIFY_REG(I2Cx->DR, I2C_DR_DR, Data); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct); -uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx); -void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* I2C1 || I2C2 || I2C3 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_I2C_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_i2c.h + * @author MCD Application Team + * @brief Header file of I2C LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_I2C_H +#define __STM32F4xx_LL_I2C_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (I2C1) || defined (I2C2) || defined (I2C3) + +/** @defgroup I2C_LL I2C + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup I2C_LL_Private_Constants I2C Private Constants + * @{ + */ + +/* Defines used to perform compute and check in the macros */ +#define LL_I2C_MAX_SPEED_STANDARD 100000U +#define LL_I2C_MAX_SPEED_FAST 400000U +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2C_LL_Private_Macros I2C Private Macros + * @{ + */ +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2C_LL_ES_INIT I2C Exported Init structure + * @{ + */ +typedef struct +{ + uint32_t PeripheralMode; /*!< Specifies the peripheral mode. + This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetMode(). */ + + uint32_t ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz (in Hz) + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetClockPeriod() + or @ref LL_I2C_SetDutyCycle() or @ref LL_I2C_SetClockSpeedMode() or @ref LL_I2C_ConfigSpeed(). */ + + uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_LL_EC_DUTYCYCLE + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetDutyCycle(). */ + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) + uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. + This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION + + This feature can be modified afterwards using unitary functions @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */ + + uint32_t DigitalFilter; /*!< Configures the digital noise filter. + This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetDigitalFilter(). */ + +#endif + uint32_t OwnAddress1; /*!< Specifies the device own address 1. + This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ + + uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. + This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE + + This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */ + + uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). + This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1 + + This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ +} LL_I2C_InitTypeDef; +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup I2C_LL_Exported_Constants I2C Exported Constants + * @{ + */ + +/** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_I2C_ReadReg function + * @{ + */ +#define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */ +#define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or + Address matched flag (slave mode) */ +#define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */ +#define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */ +#define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */ +#define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */ +#define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */ +#define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */ +#define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */ +#define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */ +#define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */ +#define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ +#define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ +#define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */ +#define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */ +#define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */ +#define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */ +#define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */ +#define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */ +#define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */ +#define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions + * @{ + */ +#define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */ +#define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */ +#define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */ +/** + * @} + */ + +#if defined(I2C_FLTR_ANOFF) +/** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection + * @{ + */ +#define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ +#define LL_I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF /*!< Analog filter is disabled.*/ +/** + * @} + */ + +#endif +/** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length + * @{ + */ +#define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */ +#define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle + * @{ + */ +#define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */ +#define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode + * @{ + */ +#define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */ +#define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode + * @{ + */ +#define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */ +#define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */ +#define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */ +#define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation + * @{ + */ +#define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */ +#define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_DIRECTION Read Write Direction + * @{ + */ +#define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */ +#define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup I2C_LL_Exported_Macros I2C Exported Macros + * @{ + */ + +/** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in I2C register + * @param __INSTANCE__ I2C Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in I2C register + * @param __INSTANCE__ I2C Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper + * @{ + */ + +/** + * @brief Convert Peripheral Clock Frequency in Mhz. + * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). + * @retval Value of peripheral clock (in Mhz) + */ +#define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U) + +/** + * @brief Convert Peripheral Clock Frequency in Hz. + * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz). + * @retval Value of peripheral clock (in Hz) + */ +#define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U) + +/** + * @brief Compute I2C Clock rising time. + * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz). + * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). + * @retval Value between Min_Data=0x02 and Max_Data=0x3F + */ +#define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) + +/** + * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value. + * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). + * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). + * @param __DUTYCYCLE__ This parameter can be one of the following values: + * @arg @ref LL_I2C_DUTYCYCLE_2 + * @arg @ref LL_I2C_DUTYCYCLE_16_9 + * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. + */ +#define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \ + (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \ + (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__)))) + +/** + * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value. + * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). + * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz). + * @retval Value between Min_Data=0x004 and Max_Data=0xFFF. + */ +#define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) + +/** + * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value. + * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). + * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz). + * @param __DUTYCYCLE__ This parameter can be one of the following values: + * @arg @ref LL_I2C_DUTYCYCLE_2 + * @arg @ref LL_I2C_DUTYCYCLE_16_9 + * @retval Value between Min_Data=0x001 and Max_Data=0xFFF + */ +#define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \ + (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \ + (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U)))) + +/** + * @brief Get the Least significant bits of a 10-Bits address. + * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +#define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF)))) + +/** + * @brief Convert a 10-Bits address to a 10-Bits header with Write direction. + * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. + * @retval Value between Min_Data=0xF0 and Max_Data=0xF6 + */ +#define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0)))) + +/** + * @brief Convert a 10-Bits address to a 10-Bits header with Read direction. + * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. + * @retval Value between Min_Data=0xF1 and Max_Data=0xF7 + */ +#define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1)))) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup I2C_LL_Exported_Functions I2C Exported Functions + * @{ + */ + +/** @defgroup I2C_LL_EF_Configuration Configuration + * @{ + */ + +/** + * @brief Enable I2C peripheral (PE = 1). + * @rmtoll CR1 PE LL_I2C_Enable + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_PE); +} + +/** + * @brief Disable I2C peripheral (PE = 0). + * @rmtoll CR1 PE LL_I2C_Disable + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE); +} + +/** + * @brief Check if the I2C peripheral is enabled or disabled. + * @rmtoll CR1 PE LL_I2C_IsEnabled + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabled(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE)); +} + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +/** + * @brief Configure Noise Filters (Analog and Digital). + * @note If the analog filter is also enabled, the digital filter is added to analog filter. + * The filters can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll FLTR ANOFF LL_I2C_ConfigFilters\n + * FLTR DNF LL_I2C_ConfigFilters + * @param I2Cx I2C Instance. + * @param AnalogFilter This parameter can be one of the following values: + * @arg @ref LL_I2C_ANALOGFILTER_ENABLE + * @arg @ref LL_I2C_ANALOGFILTER_DISABLE + * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) + * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) +{ + MODIFY_REG(I2Cx->FLTR, I2C_FLTR_ANOFF | I2C_FLTR_DNF, AnalogFilter | DigitalFilter); +} +#endif +#if defined(I2C_FLTR_DNF) + +/** + * @brief Configure Digital Noise Filter. + * @note If the analog filter is also enabled, the digital filter is added to analog filter. + * This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll FLTR DNF LL_I2C_SetDigitalFilter + * @param I2Cx I2C Instance. + * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) + * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter) +{ + MODIFY_REG(I2Cx->FLTR, I2C_FLTR_DNF, DigitalFilter); +} + +/** + * @brief Get the current Digital Noise Filter configuration. + * @rmtoll FLTR DNF LL_I2C_GetDigitalFilter + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xF + */ +__STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->FLTR, I2C_FLTR_DNF)); +} +#endif +#if defined(I2C_FLTR_ANOFF) + +/** + * @brief Enable Analog Noise Filter. + * @note This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll FLTR ANOFF LL_I2C_EnableAnalogFilter + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); +} + +/** + * @brief Disable Analog Noise Filter. + * @note This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll FLTR ANOFF LL_I2C_DisableAnalogFilter + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); +} + +/** + * @brief Check if Analog Noise Filter is enabled or disabled. + * @rmtoll FLTR ANOFF LL_I2C_IsEnabledAnalogFilter + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF) == (I2C_FLTR_ANOFF)); +} +#endif + +/** + * @brief Enable DMA transmission requests. + * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); +} + +/** + * @brief Disable DMA transmission requests. + * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); +} + +/** + * @brief Check if DMA transmission requests are enabled or disabled. + * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); +} + +/** + * @brief Enable DMA reception requests. + * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); +} + +/** + * @brief Disable DMA reception requests. + * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); +} + +/** + * @brief Check if DMA reception requests are enabled or disabled. + * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); +} + +/** + * @brief Get the data register address used for DMA transfer. + * @rmtoll DR DR LL_I2C_DMA_GetRegAddr + * @param I2Cx I2C Instance. + * @retval Address of data register + */ +__STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef *I2Cx) +{ + return (uint32_t) & (I2Cx->DR); +} + +/** + * @brief Enable Clock stretching. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); +} + +/** + * @brief Disable Clock stretching. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); +} + +/** + * @brief Check if Clock stretching is enabled or disabled. + * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH)); +} + +/** + * @brief Enable General Call. + * @note When enabled the Address 0x00 is ACKed. + * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ENGC); +} + +/** + * @brief Disable General Call. + * @note When disabled the Address 0x00 is NACKed. + * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENGC); +} + +/** + * @brief Check if General Call is enabled or disabled. + * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_ENGC) == (I2C_CR1_ENGC)); +} + +/** + * @brief Set the Own Address1. + * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n + * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n + * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n + * OAR1 ADDMODE LL_I2C_SetOwnAddress1 + * @param I2Cx I2C Instance. + * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. + * @param OwnAddrSize This parameter can be one of the following values: + * @arg @ref LL_I2C_OWNADDRESS1_7BIT + * @arg @ref LL_I2C_OWNADDRESS1_10BIT + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) +{ + MODIFY_REG(I2Cx->OAR1, I2C_OAR1_ADD0 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD8_9 | I2C_OAR1_ADDMODE, OwnAddress1 | OwnAddrSize); +} + +/** + * @brief Set the 7bits Own Address2. + * @note This action has no effect if own address2 is enabled. + * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2 + * @param I2Cx I2C Instance. + * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2) +{ + MODIFY_REG(I2Cx->OAR2, I2C_OAR2_ADD2, OwnAddress2); +} + +/** + * @brief Enable acknowledge on Own Address2 match address. + * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); +} + +/** + * @brief Disable acknowledge on Own Address2 match address. + * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); +} + +/** + * @brief Check if Own Address1 acknowledge is enabled or disabled. + * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2 + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL) == (I2C_OAR2_ENDUAL)); +} + +/** + * @brief Configure the Peripheral clock frequency. + * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock + * @param I2Cx I2C Instance. + * @param PeriphClock Peripheral Clock (in Hz) + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetPeriphClock(I2C_TypeDef *I2Cx, uint32_t PeriphClock) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock)); +} + +/** + * @brief Get the Peripheral clock frequency. + * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock + * @param I2Cx I2C Instance. + * @retval Value of Peripheral Clock (in Hz) + */ +__STATIC_INLINE uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx->CR2, I2C_CR2_FREQ))); +} + +/** + * @brief Configure the Duty cycle (Fast mode only). + * @rmtoll CCR DUTY LL_I2C_SetDutyCycle + * @param I2Cx I2C Instance. + * @param DutyCycle This parameter can be one of the following values: + * @arg @ref LL_I2C_DUTYCYCLE_2 + * @arg @ref LL_I2C_DUTYCYCLE_16_9 + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetDutyCycle(I2C_TypeDef *I2Cx, uint32_t DutyCycle) +{ + MODIFY_REG(I2Cx->CCR, I2C_CCR_DUTY, DutyCycle); +} + +/** + * @brief Get the Duty cycle (Fast mode only). + * @rmtoll CCR DUTY LL_I2C_GetDutyCycle + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_DUTYCYCLE_2 + * @arg @ref LL_I2C_DUTYCYCLE_16_9 + */ +__STATIC_INLINE uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_DUTY)); +} + +/** + * @brief Configure the I2C master clock speed mode. + * @rmtoll CCR FS LL_I2C_SetClockSpeedMode + * @param I2Cx I2C Instance. + * @param ClockSpeedMode This parameter can be one of the following values: + * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE + * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetClockSpeedMode(I2C_TypeDef *I2Cx, uint32_t ClockSpeedMode) +{ + MODIFY_REG(I2Cx->CCR, I2C_CCR_FS, ClockSpeedMode); +} + +/** + * @brief Get the the I2C master speed mode. + * @rmtoll CCR FS LL_I2C_GetClockSpeedMode + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE + * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE + */ +__STATIC_INLINE uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_FS)); +} + +/** + * @brief Configure the SCL, SDA rising time. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll TRISE TRISE LL_I2C_SetRiseTime + * @param I2Cx I2C Instance. + * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetRiseTime(I2C_TypeDef *I2Cx, uint32_t RiseTime) +{ + MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, RiseTime); +} + +/** + * @brief Get the SCL, SDA rising time. + * @rmtoll TRISE TRISE LL_I2C_GetRiseTime + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x02 and Max_Data=0x3F + */ +__STATIC_INLINE uint32_t LL_I2C_GetRiseTime(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TRISE, I2C_TRISE_TRISE)); +} + +/** + * @brief Configure the SCL high and low period. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CCR CCR LL_I2C_SetClockPeriod + * @param I2Cx I2C Instance. + * @param ClockPeriod This parameter must be a value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetClockPeriod(I2C_TypeDef *I2Cx, uint32_t ClockPeriod) +{ + MODIFY_REG(I2Cx->CCR, I2C_CCR_CCR, ClockPeriod); +} + +/** + * @brief Get the SCL high and low period. + * @rmtoll CCR CCR LL_I2C_GetClockPeriod + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. + */ +__STATIC_INLINE uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_CCR)); +} + +/** + * @brief Configure the SCL speed. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n + * TRISE TRISE LL_I2C_ConfigSpeed\n + * CCR FS LL_I2C_ConfigSpeed\n + * CCR DUTY LL_I2C_ConfigSpeed\n + * CCR CCR LL_I2C_ConfigSpeed + * @param I2Cx I2C Instance. + * @param PeriphClock Peripheral Clock (in Hz) + * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz). + * @param DutyCycle This parameter can be one of the following values: + * @arg @ref LL_I2C_DUTYCYCLE_2 + * @arg @ref LL_I2C_DUTYCYCLE_16_9 + * @retval None + */ +__STATIC_INLINE void LL_I2C_ConfigSpeed(I2C_TypeDef *I2Cx, uint32_t PeriphClock, uint32_t ClockSpeed, + uint32_t DutyCycle) +{ + uint32_t freqrange = 0x0U; + uint32_t clockconfig = 0x0U; + + /* Compute frequency range */ + freqrange = __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock); + + /* Configure I2Cx: Frequency range register */ + MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, freqrange); + + /* Configure I2Cx: Rise Time register */ + MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, __LL_I2C_RISE_TIME(freqrange, ClockSpeed)); + + /* Configure Speed mode, Duty Cycle and Clock control register value */ + if (ClockSpeed > LL_I2C_MAX_SPEED_STANDARD) + { + /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */ + clockconfig = LL_I2C_CLOCK_SPEED_FAST_MODE | \ + __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock, ClockSpeed, DutyCycle) | \ + DutyCycle; + } + else + { + /* Set Speed mode at standard for Clock Speed request in standard clock range */ + clockconfig = LL_I2C_CLOCK_SPEED_STANDARD_MODE | \ + __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock, ClockSpeed); + } + + /* Configure I2Cx: Clock control register */ + MODIFY_REG(I2Cx->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), clockconfig); +} + +/** + * @brief Configure peripheral mode. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 SMBUS LL_I2C_SetMode\n + * CR1 SMBTYPE LL_I2C_SetMode\n + * CR1 ENARP LL_I2C_SetMode + * @param I2Cx I2C Instance. + * @param PeripheralMode This parameter can be one of the following values: + * @arg @ref LL_I2C_MODE_I2C + * @arg @ref LL_I2C_MODE_SMBUS_HOST + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode) +{ + MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP, PeripheralMode); +} + +/** + * @brief Get peripheral mode. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 SMBUS LL_I2C_GetMode\n + * CR1 SMBTYPE LL_I2C_GetMode\n + * CR1 ENARP LL_I2C_GetMode + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_MODE_I2C + * @arg @ref LL_I2C_MODE_SMBUS_HOST + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP + */ +__STATIC_INLINE uint32_t LL_I2C_GetMode(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP)); +} + +/** + * @brief Enable SMBus alert (Host or Device mode) + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note SMBus Device mode: + * - SMBus Alert pin is drived low and + * Alert Response Address Header acknowledge is enabled. + * SMBus Host mode: + * - SMBus Alert pin management is supported. + * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ALERT); +} + +/** + * @brief Disable SMBus alert (Host or Device mode) + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note SMBus Device mode: + * - SMBus Alert pin is not drived (can be used as a standard GPIO) and + * Alert Response Address Header acknowledge is disabled. + * SMBus Host mode: + * - SMBus Alert pin management is not supported. + * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERT); +} + +/** + * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_ALERT) == (I2C_CR1_ALERT)); +} + +/** + * @brief Enable SMBus Packet Error Calculation (PEC). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ENPEC); +} + +/** + * @brief Disable SMBus Packet Error Calculation (PEC). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENPEC); +} + +/** + * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_ENPEC) == (I2C_CR1_ENPEC)); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_IT_Management IT_Management + * @{ + */ + +/** + * @brief Enable TXE interrupt. + * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n + * CR2 ITBUFEN LL_I2C_EnableIT_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); +} + +/** + * @brief Disable TXE interrupt. + * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n + * CR2 ITBUFEN LL_I2C_DisableIT_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); +} + +/** + * @brief Check if the TXE Interrupt is enabled or disabled. + * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n + * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); +} + +/** + * @brief Enable RXNE interrupt. + * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n + * CR2 ITBUFEN LL_I2C_EnableIT_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); +} + +/** + * @brief Disable RXNE interrupt. + * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n + * CR2 ITBUFEN LL_I2C_DisableIT_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); +} + +/** + * @brief Check if the RXNE Interrupt is enabled or disabled. + * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n + * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); +} + +/** + * @brief Enable Events interrupts. + * @note Any of these events will generate interrupt : + * Start Bit (SB) + * Address sent, Address matched (ADDR) + * 10-bit header sent (ADD10) + * Stop detection (STOPF) + * Byte transfer finished (BTF) + * + * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) : + * Receive buffer not empty (RXNE) + * Transmit buffer empty (TXE) + * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_EVT(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); +} + +/** + * @brief Disable Events interrupts. + * @note Any of these events will generate interrupt : + * Start Bit (SB) + * Address sent, Address matched (ADDR) + * 10-bit header sent (ADD10) + * Stop detection (STOPF) + * Byte transfer finished (BTF) + * Receive buffer not empty (RXNE) + * Transmit buffer empty (TXE) + * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_EVT(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); +} + +/** + * @brief Check if Events interrupts are enabled or disabled. + * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN) == (I2C_CR2_ITEVTEN)); +} + +/** + * @brief Enable Buffer interrupts. + * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) : + * Receive buffer not empty (RXNE) + * Transmit buffer empty (TXE) + * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_BUF(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); +} + +/** + * @brief Disable Buffer interrupts. + * @note Any of these Buffer events will generate interrupt : + * Receive buffer not empty (RXNE) + * Transmit buffer empty (TXE) + * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_BUF(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); +} + +/** + * @brief Check if Buffer interrupts are enabled or disabled. + * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN) == (I2C_CR2_ITBUFEN)); +} + +/** + * @brief Enable Error interrupts. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note Any of these errors will generate interrupt : + * Bus Error detection (BERR) + * Arbitration Loss (ARLO) + * Acknowledge Failure(AF) + * Overrun/Underrun (OVR) + * SMBus Timeout detection (TIMEOUT) + * SMBus PEC error detection (PECERR) + * SMBus Alert pin event detection (SMBALERT) + * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_ITERREN); +} + +/** + * @brief Disable Error interrupts. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note Any of these errors will generate interrupt : + * Bus Error detection (BERR) + * Arbitration Loss (ARLO) + * Acknowledge Failure(AF) + * Overrun/Underrun (OVR) + * SMBus Timeout detection (TIMEOUT) + * SMBus PEC error detection (PECERR) + * SMBus Alert pin event detection (SMBALERT) + * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITERREN); +} + +/** + * @brief Check if Error interrupts are enabled or disabled. + * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_ITERREN) == (I2C_CR2_ITERREN)); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_FLAG_management FLAG_management + * @{ + */ + +/** + * @brief Indicate the status of Transmit data register empty flag. + * @note RESET: When next data is written in Transmit data register. + * SET: When Transmit data register is empty. + * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_TXE) == (I2C_SR1_TXE)); +} + +/** + * @brief Indicate the status of Byte Transfer Finished flag. + * RESET: When Data byte transfer not done. + * SET: When Data byte transfer succeeded. + * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_BTF) == (I2C_SR1_BTF)); +} + +/** + * @brief Indicate the status of Receive data register not empty flag. + * @note RESET: When Receive data register is read. + * SET: When the received data is copied in Receive data register. + * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_RXNE) == (I2C_SR1_RXNE)); +} + +/** + * @brief Indicate the status of Start Bit (master mode). + * @note RESET: When No Start condition. + * SET: When Start condition is generated. + * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_SB) == (I2C_SR1_SB)); +} + +/** + * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode). + * @note RESET: Clear default value. + * SET: When the address is fully sent (master mode) or when the received slave address matched with one of the enabled slave address (slave mode). + * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_ADDR) == (I2C_SR1_ADDR)); +} + +/** + * @brief Indicate the status of 10-bit header sent (master mode). + * @note RESET: When no ADD10 event occurred. + * SET: When the master has sent the first address byte (header). + * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10 + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_ADD10) == (I2C_SR1_ADD10)); +} + +/** + * @brief Indicate the status of Acknowledge failure flag. + * @note RESET: No acknowledge failure. + * SET: When an acknowledge failure is received after a byte transmission. + * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_AF) == (I2C_SR1_AF)); +} + +/** + * @brief Indicate the status of Stop detection flag (slave mode). + * @note RESET: Clear default value. + * SET: When a Stop condition is detected. + * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_STOPF) == (I2C_SR1_STOPF)); +} + +/** + * @brief Indicate the status of Bus error flag. + * @note RESET: Clear default value. + * SET: When a misplaced Start or Stop condition is detected. + * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_BERR) == (I2C_SR1_BERR)); +} + +/** + * @brief Indicate the status of Arbitration lost flag. + * @note RESET: Clear default value. + * SET: When arbitration lost. + * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_ARLO) == (I2C_SR1_ARLO)); +} + +/** + * @brief Indicate the status of Overrun/Underrun flag. + * @note RESET: Clear default value. + * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). + * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_OVR) == (I2C_SR1_OVR)); +} + +/** + * @brief Indicate the status of SMBus PEC error flag in reception. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_PECERR) == (I2C_SR1_PECERR)); +} + +/** + * @brief Indicate the status of SMBus Timeout detection flag. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT) == (I2C_SR1_TIMEOUT)); +} + +/** + * @brief Indicate the status of SMBus alert flag. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR1, I2C_SR1_SMBALERT) == (I2C_SR1_SMBALERT)); +} + +/** + * @brief Indicate the status of Bus Busy flag. + * @note RESET: Clear default value. + * SET: When a Start condition is detected. + * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_BUSY) == (I2C_SR2_BUSY)); +} + +/** + * @brief Indicate the status of Dual flag. + * @note RESET: Received address matched with OAR1. + * SET: Received address matched with OAR2. + * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_DUALF) == (I2C_SR2_DUALF)); +} + +/** + * @brief Indicate the status of SMBus Host address reception (Slave mode). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note RESET: No SMBus Host address + * SET: SMBus Host address received. + * @note This status is cleared by hardware after a STOP condition or repeated START condition. + * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBHOST) == (I2C_SR2_SMBHOST)); +} + +/** + * @brief Indicate the status of SMBus Device default address reception (Slave mode). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note RESET: No SMBus Device default address + * SET: SMBus Device default address received. + * @note This status is cleared by hardware after a STOP condition or repeated START condition. + * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBDEFAULT) == (I2C_SR2_SMBDEFAULT)); +} + +/** + * @brief Indicate the status of General call address reception (Slave mode). + * @note RESET: No General call address + * SET: General call address received. + * @note This status is cleared by hardware after a STOP condition or repeated START condition. + * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_GENCALL) == (I2C_SR2_GENCALL)); +} + +/** + * @brief Indicate the status of Master/Slave flag. + * @note RESET: Slave Mode. + * SET: Master Mode. + * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->SR2, I2C_SR2_MSL) == (I2C_SR2_MSL)); +} + +/** + * @brief Clear Address Matched flag. + * @note Clearing this flag is done by a read access to the I2Cx_SR1 + * register followed by a read access to the I2Cx_SR2 register. + * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx) +{ + __IO uint32_t tmpreg; + tmpreg = I2Cx->SR1; + (void) tmpreg; + tmpreg = I2Cx->SR2; + (void) tmpreg; +} + +/** + * @brief Clear Acknowledge failure flag. + * @rmtoll SR1 AF LL_I2C_ClearFlag_AF + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_AF(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_AF); +} + +/** + * @brief Clear Stop detection flag. + * @note Clearing this flag is done by a read access to the I2Cx_SR1 + * register followed by a write access to I2Cx_CR1 register. + * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n + * CR1 PE LL_I2C_ClearFlag_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx) +{ + __IO uint32_t tmpreg; + tmpreg = I2Cx->SR1; + (void) tmpreg; + SET_BIT(I2Cx->CR1, I2C_CR1_PE); +} + +/** + * @brief Clear Bus error flag. + * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_BERR); +} + +/** + * @brief Clear Arbitration lost flag. + * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_ARLO); +} + +/** + * @brief Clear Overrun/Underrun flag. + * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_OVR); +} + +/** + * @brief Clear SMBus PEC error flag. + * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_PECERR); +} + +/** + * @brief Clear SMBus Timeout detection flag. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT); +} + +/** + * @brief Clear SMBus Alert flag. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->SR1, I2C_SR1_SMBALERT); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_Data_Management Data_Management + * @{ + */ + +/** + * @brief Enable Reset of I2C peripheral. + * @rmtoll CR1 SWRST LL_I2C_EnableReset + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableReset(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_SWRST); +} + +/** + * @brief Disable Reset of I2C peripheral. + * @rmtoll CR1 SWRST LL_I2C_DisableReset + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableReset(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_SWRST); +} + +/** + * @brief Check if the I2C peripheral is under reset state or not. + * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_SWRST) == (I2C_CR1_SWRST)); +} + +/** + * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. + * @note Usage in Slave or Master mode. + * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData + * @param I2Cx I2C Instance. + * @param TypeAcknowledge This parameter can be one of the following values: + * @arg @ref LL_I2C_ACK + * @arg @ref LL_I2C_NACK + * @retval None + */ +__STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge) +{ + MODIFY_REG(I2Cx->CR1, I2C_CR1_ACK, TypeAcknowledge); +} + +/** + * @brief Generate a START or RESTART condition + * @note The START bit can be set even if bus is BUSY or I2C is in slave mode. + * This action has no effect when RELOAD is set. + * @rmtoll CR1 START LL_I2C_GenerateStartCondition + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_START); +} + +/** + * @brief Generate a STOP condition after the current byte transfer (master mode). + * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_STOP); +} + +/** + * @brief Enable bit POS (master/host mode). + * @note In that case, the ACK bit controls the (N)ACK of the next byte received or the PEC bit indicates that the next byte in shift register is a PEC. + * @rmtoll CR1 POS LL_I2C_EnableBitPOS + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableBitPOS(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_POS); +} + +/** + * @brief Disable bit POS (master/host mode). + * @note In that case, the ACK bit controls the (N)ACK of the current byte received or the PEC bit indicates that the current byte in shift register is a PEC. + * @rmtoll CR1 POS LL_I2C_DisableBitPOS + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableBitPOS(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_POS); +} + +/** + * @brief Check if bit POS is enabled or disabled. + * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_POS) == (I2C_CR1_POS)); +} + +/** + * @brief Indicate the value of transfer direction. + * @note RESET: Bus is in read transfer (peripheral point of view). + * SET: Bus is in write transfer (peripheral point of view). + * @rmtoll SR2 TRA LL_I2C_GetTransferDirection + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_DIRECTION_WRITE + * @arg @ref LL_I2C_DIRECTION_READ + */ +__STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_TRA)); +} + +/** + * @brief Enable DMA last transfer. + * @note This action mean that next DMA EOT is the last transfer. + * @rmtoll CR2 LAST LL_I2C_EnableLastDMA + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableLastDMA(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_LAST); +} + +/** + * @brief Disable DMA last transfer. + * @note This action mean that next DMA EOT is not the last transfer. + * @rmtoll CR2 LAST LL_I2C_DisableLastDMA + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableLastDMA(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_LAST); +} + +/** + * @brief Check if DMA last transfer is enabled or disabled. + * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR2, I2C_CR2_LAST) == (I2C_CR2_LAST)); +} + +/** + * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note This feature is cleared by hardware when the PEC byte is transferred or compared, + * or by a START or STOP condition, it is also cleared by software. + * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_PEC); +} + +/** + * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_PEC); +} + +/** + * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef *I2Cx) +{ + return (READ_BIT(I2Cx->CR1, I2C_CR1_PEC) == (I2C_CR1_PEC)); +} + +/** + * @brief Get the SMBus Packet Error byte calculated. + * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_PEC) >> I2C_SR2_PEC_Pos); +} + +/** + * @brief Read Receive Data register. + * @rmtoll DR DR LL_I2C_ReceiveData8 + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_I2C_ReceiveData8(I2C_TypeDef *I2Cx) +{ + return (uint8_t)(READ_BIT(I2Cx->DR, I2C_DR_DR)); +} + +/** + * @brief Write in Transmit Data Register . + * @rmtoll DR DR LL_I2C_TransmitData8 + * @param I2Cx I2C Instance. + * @param Data Value between Min_Data=0x0 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data) +{ + MODIFY_REG(I2Cx->DR, I2C_DR_DR, Data); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct); +uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx); +void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct); + + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* I2C1 || I2C2 || I2C3 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_I2C_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h new file mode 100644 index 0000000..54b93e2 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h @@ -0,0 +1,302 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_iwdg.h + * @author MCD Application Team + * @brief Header file of IWDG LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_LL_IWDG_H +#define STM32F4xx_LL_IWDG_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(IWDG) + +/** @defgroup IWDG_LL IWDG + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup IWDG_LL_Private_Constants IWDG Private Constants + * @{ + */ +#define LL_IWDG_KEY_RELOAD 0x0000AAAAU /*!< IWDG Reload Counter Enable */ +#define LL_IWDG_KEY_ENABLE 0x0000CCCCU /*!< IWDG Peripheral Enable */ +#define LL_IWDG_KEY_WR_ACCESS_ENABLE 0x00005555U /*!< IWDG KR Write Access Enable */ +#define LL_IWDG_KEY_WR_ACCESS_DISABLE 0x00000000U /*!< IWDG KR Write Access Disable */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup IWDG_LL_Exported_Constants IWDG Exported Constants + * @{ + */ + +/** @defgroup IWDG_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_IWDG_ReadReg function + * @{ + */ +#define LL_IWDG_SR_PVU IWDG_SR_PVU /*!< Watchdog prescaler value update */ +#define LL_IWDG_SR_RVU IWDG_SR_RVU /*!< Watchdog counter reload value update */ +/** + * @} + */ + +/** @defgroup IWDG_LL_EC_PRESCALER Prescaler Divider + * @{ + */ +#define LL_IWDG_PRESCALER_4 0x00000000U /*!< Divider by 4 */ +#define LL_IWDG_PRESCALER_8 (IWDG_PR_PR_0) /*!< Divider by 8 */ +#define LL_IWDG_PRESCALER_16 (IWDG_PR_PR_1) /*!< Divider by 16 */ +#define LL_IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< Divider by 32 */ +#define LL_IWDG_PRESCALER_64 (IWDG_PR_PR_2) /*!< Divider by 64 */ +#define LL_IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< Divider by 128 */ +#define LL_IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< Divider by 256 */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup IWDG_LL_Exported_Macros IWDG Exported Macros + * @{ + */ + +/** @defgroup IWDG_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in IWDG register + * @param __INSTANCE__ IWDG Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_IWDG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in IWDG register + * @param __INSTANCE__ IWDG Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_IWDG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** + * @} + */ + + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup IWDG_LL_Exported_Functions IWDG Exported Functions + * @{ + */ +/** @defgroup IWDG_LL_EF_Configuration Configuration + * @{ + */ + +/** + * @brief Start the Independent Watchdog + * @note Except if the hardware watchdog option is selected + * @rmtoll KR KEY LL_IWDG_Enable + * @param IWDGx IWDG Instance + * @retval None + */ +__STATIC_INLINE void LL_IWDG_Enable(IWDG_TypeDef *IWDGx) +{ + WRITE_REG(IWDGx->KR, LL_IWDG_KEY_ENABLE); +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * @rmtoll KR KEY LL_IWDG_ReloadCounter + * @param IWDGx IWDG Instance + * @retval None + */ +__STATIC_INLINE void LL_IWDG_ReloadCounter(IWDG_TypeDef *IWDGx) +{ + WRITE_REG(IWDGx->KR, LL_IWDG_KEY_RELOAD); +} + +/** + * @brief Enable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers + * @rmtoll KR KEY LL_IWDG_EnableWriteAccess + * @param IWDGx IWDG Instance + * @retval None + */ +__STATIC_INLINE void LL_IWDG_EnableWriteAccess(IWDG_TypeDef *IWDGx) +{ + WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_ENABLE); +} + +/** + * @brief Disable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers + * @rmtoll KR KEY LL_IWDG_DisableWriteAccess + * @param IWDGx IWDG Instance + * @retval None + */ +__STATIC_INLINE void LL_IWDG_DisableWriteAccess(IWDG_TypeDef *IWDGx) +{ + WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_DISABLE); +} + +/** + * @brief Select the prescaler of the IWDG + * @rmtoll PR PR LL_IWDG_SetPrescaler + * @param IWDGx IWDG Instance + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_IWDG_PRESCALER_4 + * @arg @ref LL_IWDG_PRESCALER_8 + * @arg @ref LL_IWDG_PRESCALER_16 + * @arg @ref LL_IWDG_PRESCALER_32 + * @arg @ref LL_IWDG_PRESCALER_64 + * @arg @ref LL_IWDG_PRESCALER_128 + * @arg @ref LL_IWDG_PRESCALER_256 + * @retval None + */ +__STATIC_INLINE void LL_IWDG_SetPrescaler(IWDG_TypeDef *IWDGx, uint32_t Prescaler) +{ + WRITE_REG(IWDGx->PR, IWDG_PR_PR & Prescaler); +} + +/** + * @brief Get the selected prescaler of the IWDG + * @rmtoll PR PR LL_IWDG_GetPrescaler + * @param IWDGx IWDG Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_IWDG_PRESCALER_4 + * @arg @ref LL_IWDG_PRESCALER_8 + * @arg @ref LL_IWDG_PRESCALER_16 + * @arg @ref LL_IWDG_PRESCALER_32 + * @arg @ref LL_IWDG_PRESCALER_64 + * @arg @ref LL_IWDG_PRESCALER_128 + * @arg @ref LL_IWDG_PRESCALER_256 + */ +__STATIC_INLINE uint32_t LL_IWDG_GetPrescaler(IWDG_TypeDef *IWDGx) +{ + return (READ_REG(IWDGx->PR)); +} + +/** + * @brief Specify the IWDG down-counter reload value + * @rmtoll RLR RL LL_IWDG_SetReloadCounter + * @param IWDGx IWDG Instance + * @param Counter Value between Min_Data=0 and Max_Data=0x0FFF + * @retval None + */ +__STATIC_INLINE void LL_IWDG_SetReloadCounter(IWDG_TypeDef *IWDGx, uint32_t Counter) +{ + WRITE_REG(IWDGx->RLR, IWDG_RLR_RL & Counter); +} + +/** + * @brief Get the specified IWDG down-counter reload value + * @rmtoll RLR RL LL_IWDG_GetReloadCounter + * @param IWDGx IWDG Instance + * @retval Value between Min_Data=0 and Max_Data=0x0FFF + */ +__STATIC_INLINE uint32_t LL_IWDG_GetReloadCounter(IWDG_TypeDef *IWDGx) +{ + return (READ_REG(IWDGx->RLR)); +} + +/** + * @} + */ + +/** @defgroup IWDG_LL_EF_FLAG_Management FLAG_Management + * @{ + */ + +/** + * @brief Check if flag Prescaler Value Update is set or not + * @rmtoll SR PVU LL_IWDG_IsActiveFlag_PVU + * @param IWDGx IWDG Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_PVU(IWDG_TypeDef *IWDGx) +{ + return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU) == (IWDG_SR_PVU)) ? 1UL : 0UL); +} + +/** + * @brief Check if flag Reload Value Update is set or not + * @rmtoll SR RVU LL_IWDG_IsActiveFlag_RVU + * @param IWDGx IWDG Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_RVU(IWDG_TypeDef *IWDGx) +{ + return ((READ_BIT(IWDGx->SR, IWDG_SR_RVU) == (IWDG_SR_RVU)) ? 1UL : 0UL); +} + +/** + * @brief Check if flags Prescaler & Reload Value Update are reset or not + * @rmtoll SR PVU LL_IWDG_IsReady\n + * SR RVU LL_IWDG_IsReady + * @param IWDGx IWDG Instance + * @retval State of bits (1 or 0). + */ +__STATIC_INLINE uint32_t LL_IWDG_IsReady(IWDG_TypeDef *IWDGx) +{ + return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU | IWDG_SR_RVU) == 0U) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* IWDG */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_LL_IWDG_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h index ea23dc5..f40e079 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h @@ -1,985 +1,985 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_pwr.h - * @author MCD Application Team - * @brief Header file of PWR LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_PWR_H -#define __STM32F4xx_LL_PWR_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(PWR) - -/** @defgroup PWR_LL PWR - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_PWR_WriteReg function - * @{ - */ -#define LL_PWR_CR_CSBF PWR_CR_CSBF /*!< Clear standby flag */ -#define LL_PWR_CR_CWUF PWR_CR_CWUF /*!< Clear wakeup flag */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_PWR_ReadReg function - * @{ - */ -#define LL_PWR_CSR_WUF PWR_CSR_WUF /*!< Wakeup flag */ -#define LL_PWR_CSR_SBF PWR_CSR_SBF /*!< Standby flag */ -#define LL_PWR_CSR_PVDO PWR_CSR_PVDO /*!< Power voltage detector output flag */ -#define LL_PWR_CSR_VOS PWR_CSR_VOSRDY /*!< Voltage scaling select flag */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP /*!< Enable WKUP pin */ -#elif defined(PWR_CSR_EWUP1) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP1 /*!< Enable WKUP pin 1 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_CSR_EWUP2 PWR_CSR_EWUP2 /*!< Enable WKUP pin 2 */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_CSR_EWUP3 PWR_CSR_EWUP3 /*!< Enable WKUP pin 3 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_VOLTAGE Regulator Voltage - * @{ - */ -#if defined(PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE3 (PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE2 (PWR_CR_VOS_1) -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS_0 | PWR_CR_VOS_1) /* The SCALE1 is not available for STM32F401xx devices */ -#else -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS) -#define LL_PWR_REGU_VOLTAGE_SCALE2 0x00000000U -#endif /* PWR_CR_VOS_0 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_MODE_PWR Mode Power - * @{ - */ -#define LL_PWR_MODE_STOP_MAINREGU 0x00000000U /*!< Enter Stop mode when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU (PWR_CR_LPDS) /*!< Enter Stop mode (with low power Regulator ON) when the CPU enters deepsleep */ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (PWR_CR_MRUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in under-drive mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in under-drive mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -#if defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (PWR_CR_MRLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (PWR_CR_LPDS | PWR_CR_LPLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRLVDS && PWR_CR_LPLVDS && PWR_CR_FPDS */ -#define LL_PWR_MODE_STANDBY (PWR_CR_PDDS) /*!< Enter Standby mode when the CPU enters deepsleep */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_MODE_DS_MODE Regulator Mode In Deep Sleep Mode - * @{ - */ -#define LL_PWR_REGU_DSMODE_MAIN 0x00000000U /*!< Voltage Regulator in main mode during deepsleep mode */ -#define LL_PWR_REGU_DSMODE_LOW_POWER (PWR_CR_LPDS) /*!< Voltage Regulator in low-power mode during deepsleep mode */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_PVDLEVEL Power Voltage Detector Level - * @{ - */ -#define LL_PWR_PVDLEVEL_0 (PWR_CR_PLS_LEV0) /*!< Voltage threshold detected by PVD 2.2 V */ -#define LL_PWR_PVDLEVEL_1 (PWR_CR_PLS_LEV1) /*!< Voltage threshold detected by PVD 2.3 V */ -#define LL_PWR_PVDLEVEL_2 (PWR_CR_PLS_LEV2) /*!< Voltage threshold detected by PVD 2.4 V */ -#define LL_PWR_PVDLEVEL_3 (PWR_CR_PLS_LEV3) /*!< Voltage threshold detected by PVD 2.5 V */ -#define LL_PWR_PVDLEVEL_4 (PWR_CR_PLS_LEV4) /*!< Voltage threshold detected by PVD 2.6 V */ -#define LL_PWR_PVDLEVEL_5 (PWR_CR_PLS_LEV5) /*!< Voltage threshold detected by PVD 2.7 V */ -#define LL_PWR_PVDLEVEL_6 (PWR_CR_PLS_LEV6) /*!< Voltage threshold detected by PVD 2.8 V */ -#define LL_PWR_PVDLEVEL_7 (PWR_CR_PLS_LEV7) /*!< Voltage threshold detected by PVD 2.9 V */ -/** - * @} - */ -/** @defgroup PWR_LL_EC_WAKEUP_PIN Wakeup Pins - * @{ - */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP) /*!< WKUP pin : PA0 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP1) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP1) /*!< WKUP pin 1 : PA0 */ -#endif /* PWR_CSR_EWUP1 */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_WAKEUP_PIN2 (PWR_CSR_EWUP2) /*!< WKUP pin 2 : PC0 or PC13 according to device */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_WAKEUP_PIN3 (PWR_CSR_EWUP3) /*!< WKUP pin 3 : PC1 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** - * @} - */ - - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Macros PWR Exported Macros - * @{ - */ - -/** @defgroup PWR_LL_EM_WRITE_READ Common write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in PWR register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_PWR_WriteReg(__REG__, __VALUE__) WRITE_REG(PWR->__REG__, (__VALUE__)) - -/** - * @brief Read a value in PWR register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_PWR_ReadReg(__REG__) READ_REG(PWR->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @defgroup PWR_LL_EF_Configuration Configuration - * @{ - */ -#if defined(PWR_CR_FISSR) -/** - * @brief Enable FLASH interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_EnableFLASHInterfaceSTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHInterfaceSTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Disable FLASH Interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_DisableFLASHInterfaceSTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHInterfaceSTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Check if FLASH Interface STOP while system Run feature is enabled - * @rmtoll CR FISSR LL_PWR_IsEnabledFLASHInterfaceSTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHInterfaceSTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FISSR) == (PWR_CR_FISSR)); -} -#endif /* PWR_CR_FISSR */ - -#if defined(PWR_CR_FMSSR) -/** - * @brief Enable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_EnableFLASHMemorySTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHMemorySTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Disable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_DisableFLASHMemorySTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHMemorySTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Check if FLASH Memory STOP while system Run feature is enabled - * @rmtoll CR FMSSR LL_PWR_IsEnabledFLASHMemorySTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHMemorySTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FMSSR) == (PWR_CR_FMSSR)); -} -#endif /* PWR_CR_FMSSR */ -#if defined(PWR_CR_UDEN) -/** - * @brief Enable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_EnableUnderDriveMode - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main Regulator or the low power Regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage Regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableUnderDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Disable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_DisableUnderDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableUnderDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Check if Under Drive Mode is enabled - * @rmtoll CR UDEN LL_PWR_IsEnabledUnderDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledUnderDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_UDEN) == (PWR_CR_UDEN)); -} -#endif /* PWR_CR_UDEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Enable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_EnableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveSwitching(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Disable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_DisableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveSwitching(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODSWEN LL_PWR_IsEnabledOverDriveSwitching - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveSwitching(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODSWEN) == (PWR_CR_ODSWEN)); -} -#endif /* PWR_CR_ODSWEN */ -#if defined(PWR_CR_ODEN) -/** - * @brief Enable Over drive Mode - * @rmtoll CR ODEN LL_PWR_EnableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Disable Over drive Mode - * @rmtoll CR ODEN LL_PWR_DisableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODEN LL_PWR_IsEnabledOverDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODEN) == (PWR_CR_ODEN)); -} -#endif /* PWR_CR_ODEN */ -#if defined(PWR_CR_MRUDS) -/** - * @brief Enable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_EnableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Disable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_DisableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Check if Main Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR MRUDS LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRUDS) == (PWR_CR_MRUDS)); -} -#endif /* PWR_CR_MRUDS */ - -#if defined(PWR_CR_LPUDS) -/** - * @brief Enable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Disable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Check if Low Power Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR LPUDS LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPUDS) == (PWR_CR_LPUDS)); -} -#endif /* PWR_CR_LPUDS */ - -#if defined(PWR_CR_MRLVDS) -/** - * @brief Enable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_EnableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Disable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_DisableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Check if Main Regulator low voltage Mode is enabled - * @rmtoll CR MRLVDS LL_PWR_IsEnabledMainRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRLVDS) == (PWR_CR_MRLVDS)); -} -#endif /* PWR_CR_MRLVDS */ - -#if defined(PWR_CR_LPLVDS) -/** - * @brief Enable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_EnableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Disable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_DisableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Check if Low Power Regulator low voltage Mode is enabled - * @rmtoll CR LPLVDS LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPLVDS) == (PWR_CR_LPLVDS)); -} -#endif /* PWR_CR_LPLVDS */ -/** - * @brief Set the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_SetRegulVoltageScaling - * @param VoltageScaling This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulVoltageScaling(uint32_t VoltageScaling) -{ - MODIFY_REG(PWR->CR, PWR_CR_VOS, VoltageScaling); -} - -/** - * @brief Get the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_GetRegulVoltageScaling - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulVoltageScaling(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_VOS)); -} -/** - * @brief Enable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_EnableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFlashPowerDown(void) -{ - SET_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Disable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_DisableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFlashPowerDown(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Check if the Flash Power Down in Stop Mode is enabled - * @rmtoll CR FPDS LL_PWR_IsEnabledFlashPowerDown - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFlashPowerDown(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FPDS) == (PWR_CR_FPDS)); -} - -/** - * @brief Enable access to the backup domain - * @rmtoll CR DBP LL_PWR_EnableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpAccess(void) -{ - SET_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Disable access to the backup domain - * @rmtoll CR DBP LL_PWR_DisableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpAccess(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Check if the backup domain is enabled - * @rmtoll CR DBP LL_PWR_IsEnabledBkUpAccess - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpAccess(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_DBP) == (PWR_CR_DBP)); -} -/** - * @brief Enable the backup Regulator - * @rmtoll CSR BRE LL_PWR_EnableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpRegulator(void) -{ - SET_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Disable the backup Regulator - * @rmtoll CSR BRE LL_PWR_DisableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpRegulator(void) -{ - CLEAR_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Check if the backup Regulator is enabled - * @rmtoll CSR BRE LL_PWR_IsEnabledBkUpRegulator - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpRegulator(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRE) == (PWR_CSR_BRE)); -} - -/** - * @brief Set voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_SetRegulModeDS - * @param RegulMode This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulModeDS(uint32_t RegulMode) -{ - MODIFY_REG(PWR->CR, PWR_CR_LPDS, RegulMode); -} - -/** - * @brief Get voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_GetRegulModeDS - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulModeDS(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_LPDS)); -} - -/** - * @brief Set Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPlVDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPDS LL_PWR_SetPowerMode - * @param PDMode This parameter can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPowerMode(uint32_t PDMode) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS), PDMode); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS), PDMode); -#else - MODIFY_REG(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS), PDMode); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Get Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPDS LL_PWR_GetPowerMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - */ -__STATIC_INLINE uint32_t LL_PWR_GetPowerMode(void) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS))); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS))); -#else - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS))); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Configure the voltage threshold detected by the Power Voltage Detector - * @rmtoll CR PLS LL_PWR_SetPVDLevel - * @param PVDLevel This parameter can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPVDLevel(uint32_t PVDLevel) -{ - MODIFY_REG(PWR->CR, PWR_CR_PLS, PVDLevel); -} - -/** - * @brief Get the voltage threshold detection - * @rmtoll CR PLS LL_PWR_GetPVDLevel - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - */ -__STATIC_INLINE uint32_t LL_PWR_GetPVDLevel(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_PLS)); -} - -/** - * @brief Enable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_EnablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnablePVD(void) -{ - SET_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Disable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_DisablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisablePVD(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Check if Power Voltage Detector is enabled - * @rmtoll CR PVDE LL_PWR_IsEnabledPVD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledPVD(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_PVDE) == (PWR_CR_PVDE)); -} - -/** - * @brief Enable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_EnableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableWakeUpPin(uint32_t WakeUpPin) -{ - SET_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Disable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_DisableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableWakeUpPin(uint32_t WakeUpPin) -{ - CLEAR_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Check if the WakeUp PINx functionality is enabled - * @rmtoll CSR EWUP LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_IsEnabledWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledWakeUpPin(uint32_t WakeUpPin) -{ - return (READ_BIT(PWR->CSR, WakeUpPin) == (WakeUpPin)); -} - - -/** - * @} - */ - -/** @defgroup PWR_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Wake-up Flag - * @rmtoll CSR WUF LL_PWR_IsActiveFlag_WU - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_WU(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_WUF) == (PWR_CSR_WUF)); -} - -/** - * @brief Get Standby Flag - * @rmtoll CSR SBF LL_PWR_IsActiveFlag_SB - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_SB(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_SBF) == (PWR_CSR_SBF)); -} - -/** - * @brief Get Backup Regulator ready Flag - * @rmtoll CSR BRR LL_PWR_IsActiveFlag_BRR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_BRR(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRR) == (PWR_CSR_BRR)); -} -/** - * @brief Indicate whether VDD voltage is below the selected PVD threshold - * @rmtoll CSR PVDO LL_PWR_IsActiveFlag_PVDO - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_PVDO(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_PVDO) == (PWR_CSR_PVDO)); -} - -/** - * @brief Indicate whether the Regulator is ready in the selected voltage range or if its output voltage is still changing to the required voltage level - * @rmtoll CSR VOS LL_PWR_IsActiveFlag_VOS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_VOS(void) -{ - return (READ_BIT(PWR->CSR, LL_PWR_CSR_VOS) == (LL_PWR_CSR_VOS)); -} -#if defined(PWR_CR_ODEN) -/** - * @brief Indicate whether the Over-Drive mode is ready or not - * @rmtoll CSR ODRDY LL_PWR_IsActiveFlag_OD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_OD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODRDY) == (PWR_CSR_ODRDY)); -} -#endif /* PWR_CR_ODEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Indicate whether the Over-Drive mode switching is ready or not - * @rmtoll CSR ODSWRDY LL_PWR_IsActiveFlag_ODSW - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_ODSW(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODSWRDY) == (PWR_CSR_ODSWRDY)); -} -#endif /* PWR_CR_ODSWEN */ - -#if defined(PWR_CR_UDEN) -/** - * @brief Indicate whether the Under-Drive mode is ready or not - * @rmtoll CSR UDRDY LL_PWR_IsActiveFlag_UD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_UD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_UDRDY) == (PWR_CSR_UDRDY)); -} -#endif /* PWR_CR_UDEN */ -/** - * @brief Clear Standby Flag - * @rmtoll CR CSBF LL_PWR_ClearFlag_SB - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_SB(void) -{ - SET_BIT(PWR->CR, PWR_CR_CSBF); -} - -/** - * @brief Clear Wake-up Flags - * @rmtoll CR CWUF LL_PWR_ClearFlag_WU - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_WU(void) -{ - SET_BIT(PWR->CR, PWR_CR_CWUF); -} -#if defined(PWR_CSR_UDRDY) -/** - * @brief Clear Under-Drive ready Flag - * @rmtoll CSR UDRDY LL_PWR_ClearFlag_UD - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_UD(void) -{ - WRITE_REG(PWR->CSR, PWR_CSR_UDRDY); -} -#endif /* PWR_CSR_UDRDY */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup PWR_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_PWR_DeInit(void); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(PWR) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_PWR_H */ +/** + ****************************************************************************** + * @file stm32f4xx_ll_pwr.h + * @author MCD Application Team + * @brief Header file of PWR LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_PWR_H +#define __STM32F4xx_LL_PWR_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(PWR) + +/** @defgroup PWR_LL PWR + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup PWR_LL_Exported_Constants PWR Exported Constants + * @{ + */ + +/** @defgroup PWR_LL_EC_CLEAR_FLAG Clear Flags Defines + * @brief Flags defines which can be used with LL_PWR_WriteReg function + * @{ + */ +#define LL_PWR_CR_CSBF PWR_CR_CSBF /*!< Clear standby flag */ +#define LL_PWR_CR_CWUF PWR_CR_CWUF /*!< Clear wakeup flag */ +/** + * @} + */ + +/** @defgroup PWR_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_PWR_ReadReg function + * @{ + */ +#define LL_PWR_CSR_WUF PWR_CSR_WUF /*!< Wakeup flag */ +#define LL_PWR_CSR_SBF PWR_CSR_SBF /*!< Standby flag */ +#define LL_PWR_CSR_PVDO PWR_CSR_PVDO /*!< Power voltage detector output flag */ +#define LL_PWR_CSR_VOS PWR_CSR_VOSRDY /*!< Voltage scaling select flag */ +#if defined(PWR_CSR_EWUP) +#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP /*!< Enable WKUP pin */ +#elif defined(PWR_CSR_EWUP1) +#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP1 /*!< Enable WKUP pin 1 */ +#endif /* PWR_CSR_EWUP */ +#if defined(PWR_CSR_EWUP2) +#define LL_PWR_CSR_EWUP2 PWR_CSR_EWUP2 /*!< Enable WKUP pin 2 */ +#endif /* PWR_CSR_EWUP2 */ +#if defined(PWR_CSR_EWUP3) +#define LL_PWR_CSR_EWUP3 PWR_CSR_EWUP3 /*!< Enable WKUP pin 3 */ +#endif /* PWR_CSR_EWUP3 */ +/** + * @} + */ + +/** @defgroup PWR_LL_EC_REGU_VOLTAGE Regulator Voltage + * @{ + */ +#if defined(PWR_CR_VOS_0) +#define LL_PWR_REGU_VOLTAGE_SCALE3 (PWR_CR_VOS_0) +#define LL_PWR_REGU_VOLTAGE_SCALE2 (PWR_CR_VOS_1) +#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS_0 | PWR_CR_VOS_1) /* The SCALE1 is not available for STM32F401xx devices */ +#else +#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS) +#define LL_PWR_REGU_VOLTAGE_SCALE2 0x00000000U +#endif /* PWR_CR_VOS_0 */ +/** + * @} + */ + +/** @defgroup PWR_LL_EC_MODE_PWR Mode Power + * @{ + */ +#define LL_PWR_MODE_STOP_MAINREGU 0x00000000U /*!< Enter Stop mode when the CPU enters deepsleep */ +#define LL_PWR_MODE_STOP_LPREGU (PWR_CR_LPDS) /*!< Enter Stop mode (with low power Regulator ON) when the CPU enters deepsleep */ +#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) +#define LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (PWR_CR_MRUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in under-drive mode) when the CPU enters deepsleep */ +#define LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in under-drive mode) when the CPU enters deepsleep */ +#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ +#if defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) +#define LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (PWR_CR_MRLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in Deep Sleep mode) when the CPU enters deepsleep */ +#define LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (PWR_CR_LPDS | PWR_CR_LPLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in Deep Sleep mode) when the CPU enters deepsleep */ +#endif /* PWR_CR_MRLVDS && PWR_CR_LPLVDS && PWR_CR_FPDS */ +#define LL_PWR_MODE_STANDBY (PWR_CR_PDDS) /*!< Enter Standby mode when the CPU enters deepsleep */ +/** + * @} + */ + +/** @defgroup PWR_LL_EC_REGU_MODE_DS_MODE Regulator Mode In Deep Sleep Mode + * @{ + */ +#define LL_PWR_REGU_DSMODE_MAIN 0x00000000U /*!< Voltage Regulator in main mode during deepsleep mode */ +#define LL_PWR_REGU_DSMODE_LOW_POWER (PWR_CR_LPDS) /*!< Voltage Regulator in low-power mode during deepsleep mode */ +/** + * @} + */ + +/** @defgroup PWR_LL_EC_PVDLEVEL Power Voltage Detector Level + * @{ + */ +#define LL_PWR_PVDLEVEL_0 (PWR_CR_PLS_LEV0) /*!< Voltage threshold detected by PVD 2.2 V */ +#define LL_PWR_PVDLEVEL_1 (PWR_CR_PLS_LEV1) /*!< Voltage threshold detected by PVD 2.3 V */ +#define LL_PWR_PVDLEVEL_2 (PWR_CR_PLS_LEV2) /*!< Voltage threshold detected by PVD 2.4 V */ +#define LL_PWR_PVDLEVEL_3 (PWR_CR_PLS_LEV3) /*!< Voltage threshold detected by PVD 2.5 V */ +#define LL_PWR_PVDLEVEL_4 (PWR_CR_PLS_LEV4) /*!< Voltage threshold detected by PVD 2.6 V */ +#define LL_PWR_PVDLEVEL_5 (PWR_CR_PLS_LEV5) /*!< Voltage threshold detected by PVD 2.7 V */ +#define LL_PWR_PVDLEVEL_6 (PWR_CR_PLS_LEV6) /*!< Voltage threshold detected by PVD 2.8 V */ +#define LL_PWR_PVDLEVEL_7 (PWR_CR_PLS_LEV7) /*!< Voltage threshold detected by PVD 2.9 V */ +/** + * @} + */ +/** @defgroup PWR_LL_EC_WAKEUP_PIN Wakeup Pins + * @{ + */ +#if defined(PWR_CSR_EWUP) +#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP) /*!< WKUP pin : PA0 */ +#endif /* PWR_CSR_EWUP */ +#if defined(PWR_CSR_EWUP1) +#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP1) /*!< WKUP pin 1 : PA0 */ +#endif /* PWR_CSR_EWUP1 */ +#if defined(PWR_CSR_EWUP2) +#define LL_PWR_WAKEUP_PIN2 (PWR_CSR_EWUP2) /*!< WKUP pin 2 : PC0 or PC13 according to device */ +#endif /* PWR_CSR_EWUP2 */ +#if defined(PWR_CSR_EWUP3) +#define LL_PWR_WAKEUP_PIN3 (PWR_CSR_EWUP3) /*!< WKUP pin 3 : PC1 */ +#endif /* PWR_CSR_EWUP3 */ +/** + * @} + */ + +/** + * @} + */ + + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup PWR_LL_Exported_Macros PWR Exported Macros + * @{ + */ + +/** @defgroup PWR_LL_EM_WRITE_READ Common write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in PWR register + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_PWR_WriteReg(__REG__, __VALUE__) WRITE_REG(PWR->__REG__, (__VALUE__)) + +/** + * @brief Read a value in PWR register + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_PWR_ReadReg(__REG__) READ_REG(PWR->__REG__) +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup PWR_LL_Exported_Functions PWR Exported Functions + * @{ + */ + +/** @defgroup PWR_LL_EF_Configuration Configuration + * @{ + */ +#if defined(PWR_CR_FISSR) +/** + * @brief Enable FLASH interface STOP while system Run is ON + * @rmtoll CR FISSR LL_PWR_EnableFLASHInterfaceSTOP + * @note This mode is enabled only with STOP low power mode. + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableFLASHInterfaceSTOP(void) +{ + SET_BIT(PWR->CR, PWR_CR_FISSR); +} + +/** + * @brief Disable FLASH Interface STOP while system Run is ON + * @rmtoll CR FISSR LL_PWR_DisableFLASHInterfaceSTOP + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableFLASHInterfaceSTOP(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_FISSR); +} + +/** + * @brief Check if FLASH Interface STOP while system Run feature is enabled + * @rmtoll CR FISSR LL_PWR_IsEnabledFLASHInterfaceSTOP + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHInterfaceSTOP(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_FISSR) == (PWR_CR_FISSR)); +} +#endif /* PWR_CR_FISSR */ + +#if defined(PWR_CR_FMSSR) +/** + * @brief Enable FLASH Memory STOP while system Run is ON + * @rmtoll CR FMSSR LL_PWR_EnableFLASHMemorySTOP + * @note This mode is enabled only with STOP low power mode. + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableFLASHMemorySTOP(void) +{ + SET_BIT(PWR->CR, PWR_CR_FMSSR); +} + +/** + * @brief Disable FLASH Memory STOP while system Run is ON + * @rmtoll CR FMSSR LL_PWR_DisableFLASHMemorySTOP + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableFLASHMemorySTOP(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); +} + +/** + * @brief Check if FLASH Memory STOP while system Run feature is enabled + * @rmtoll CR FMSSR LL_PWR_IsEnabledFLASHMemorySTOP + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHMemorySTOP(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_FMSSR) == (PWR_CR_FMSSR)); +} +#endif /* PWR_CR_FMSSR */ +#if defined(PWR_CR_UDEN) +/** + * @brief Enable Under Drive Mode + * @rmtoll CR UDEN LL_PWR_EnableUnderDriveMode + * @note This mode is enabled only with STOP low power mode. + * In this mode, the 1.2V domain is preserved in reduced leakage mode. This + * mode is only available when the main Regulator or the low power Regulator + * is in low voltage mode. + * @note If the Under-drive mode was enabled, it is automatically disabled after + * exiting Stop mode. + * When the voltage Regulator operates in Under-drive mode, an additional + * startup delay is induced when waking up from Stop mode. + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableUnderDriveMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_UDEN); +} + +/** + * @brief Disable Under Drive Mode + * @rmtoll CR UDEN LL_PWR_DisableUnderDriveMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableUnderDriveMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_UDEN); +} + +/** + * @brief Check if Under Drive Mode is enabled + * @rmtoll CR UDEN LL_PWR_IsEnabledUnderDriveMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledUnderDriveMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_UDEN) == (PWR_CR_UDEN)); +} +#endif /* PWR_CR_UDEN */ + +#if defined(PWR_CR_ODSWEN) +/** + * @brief Enable Over drive switching + * @rmtoll CR ODSWEN LL_PWR_EnableOverDriveSwitching + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableOverDriveSwitching(void) +{ + SET_BIT(PWR->CR, PWR_CR_ODSWEN); +} + +/** + * @brief Disable Over drive switching + * @rmtoll CR ODSWEN LL_PWR_DisableOverDriveSwitching + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableOverDriveSwitching(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_ODSWEN); +} + +/** + * @brief Check if Over drive switching is enabled + * @rmtoll CR ODSWEN LL_PWR_IsEnabledOverDriveSwitching + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveSwitching(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_ODSWEN) == (PWR_CR_ODSWEN)); +} +#endif /* PWR_CR_ODSWEN */ +#if defined(PWR_CR_ODEN) +/** + * @brief Enable Over drive Mode + * @rmtoll CR ODEN LL_PWR_EnableOverDriveMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableOverDriveMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_ODEN); +} + +/** + * @brief Disable Over drive Mode + * @rmtoll CR ODEN LL_PWR_DisableOverDriveMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableOverDriveMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_ODEN); +} + +/** + * @brief Check if Over drive switching is enabled + * @rmtoll CR ODEN LL_PWR_IsEnabledOverDriveMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_ODEN) == (PWR_CR_ODEN)); +} +#endif /* PWR_CR_ODEN */ +#if defined(PWR_CR_MRUDS) +/** + * @brief Enable Main Regulator in deepsleep under-drive Mode + * @rmtoll CR MRUDS LL_PWR_EnableMainRegulatorDeepSleepUDMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableMainRegulatorDeepSleepUDMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_MRUDS); +} + +/** + * @brief Disable Main Regulator in deepsleep under-drive Mode + * @rmtoll CR MRUDS LL_PWR_DisableMainRegulatorDeepSleepUDMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableMainRegulatorDeepSleepUDMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_MRUDS); +} + +/** + * @brief Check if Main Regulator in deepsleep under-drive Mode is enabled + * @rmtoll CR MRUDS LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_MRUDS) == (PWR_CR_MRUDS)); +} +#endif /* PWR_CR_MRUDS */ + +#if defined(PWR_CR_LPUDS) +/** + * @brief Enable Low Power Regulator in deepsleep under-drive Mode + * @rmtoll CR LPUDS LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_LPUDS); +} + +/** + * @brief Disable Low Power Regulator in deepsleep under-drive Mode + * @rmtoll CR LPUDS LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_LPUDS); +} + +/** + * @brief Check if Low Power Regulator in deepsleep under-drive Mode is enabled + * @rmtoll CR LPUDS LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_LPUDS) == (PWR_CR_LPUDS)); +} +#endif /* PWR_CR_LPUDS */ + +#if defined(PWR_CR_MRLVDS) +/** + * @brief Enable Main Regulator low voltage Mode + * @rmtoll CR MRLVDS LL_PWR_EnableMainRegulatorLowVoltageMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableMainRegulatorLowVoltageMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_MRLVDS); +} + +/** + * @brief Disable Main Regulator low voltage Mode + * @rmtoll CR MRLVDS LL_PWR_DisableMainRegulatorLowVoltageMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableMainRegulatorLowVoltageMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_MRLVDS); +} + +/** + * @brief Check if Main Regulator low voltage Mode is enabled + * @rmtoll CR MRLVDS LL_PWR_IsEnabledMainRegulatorLowVoltageMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorLowVoltageMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_MRLVDS) == (PWR_CR_MRLVDS)); +} +#endif /* PWR_CR_MRLVDS */ + +#if defined(PWR_CR_LPLVDS) +/** + * @brief Enable Low Power Regulator low voltage Mode + * @rmtoll CR LPLVDS LL_PWR_EnableLowPowerRegulatorLowVoltageMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorLowVoltageMode(void) +{ + SET_BIT(PWR->CR, PWR_CR_LPLVDS); +} + +/** + * @brief Disable Low Power Regulator low voltage Mode + * @rmtoll CR LPLVDS LL_PWR_DisableLowPowerRegulatorLowVoltageMode + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorLowVoltageMode(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_LPLVDS); +} + +/** + * @brief Check if Low Power Regulator low voltage Mode is enabled + * @rmtoll CR LPLVDS LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_LPLVDS) == (PWR_CR_LPLVDS)); +} +#endif /* PWR_CR_LPLVDS */ +/** + * @brief Set the main internal Regulator output voltage + * @rmtoll CR VOS LL_PWR_SetRegulVoltageScaling + * @param VoltageScaling This parameter can be one of the following values: + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 + * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices + * @retval None + */ +__STATIC_INLINE void LL_PWR_SetRegulVoltageScaling(uint32_t VoltageScaling) +{ + MODIFY_REG(PWR->CR, PWR_CR_VOS, VoltageScaling); +} + +/** + * @brief Get the main internal Regulator output voltage + * @rmtoll CR VOS LL_PWR_GetRegulVoltageScaling + * @retval Returned value can be one of the following values: + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 + * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 + * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices + */ +__STATIC_INLINE uint32_t LL_PWR_GetRegulVoltageScaling(void) +{ + return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_VOS)); +} +/** + * @brief Enable the Flash Power Down in Stop Mode + * @rmtoll CR FPDS LL_PWR_EnableFlashPowerDown + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableFlashPowerDown(void) +{ + SET_BIT(PWR->CR, PWR_CR_FPDS); +} + +/** + * @brief Disable the Flash Power Down in Stop Mode + * @rmtoll CR FPDS LL_PWR_DisableFlashPowerDown + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableFlashPowerDown(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_FPDS); +} + +/** + * @brief Check if the Flash Power Down in Stop Mode is enabled + * @rmtoll CR FPDS LL_PWR_IsEnabledFlashPowerDown + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledFlashPowerDown(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_FPDS) == (PWR_CR_FPDS)); +} + +/** + * @brief Enable access to the backup domain + * @rmtoll CR DBP LL_PWR_EnableBkUpAccess + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableBkUpAccess(void) +{ + SET_BIT(PWR->CR, PWR_CR_DBP); +} + +/** + * @brief Disable access to the backup domain + * @rmtoll CR DBP LL_PWR_DisableBkUpAccess + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableBkUpAccess(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_DBP); +} + +/** + * @brief Check if the backup domain is enabled + * @rmtoll CR DBP LL_PWR_IsEnabledBkUpAccess + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpAccess(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_DBP) == (PWR_CR_DBP)); +} +/** + * @brief Enable the backup Regulator + * @rmtoll CSR BRE LL_PWR_EnableBkUpRegulator + * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. + * The LL_PWR_EnableBkUpAccess() must be called before using this API. + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableBkUpRegulator(void) +{ + SET_BIT(PWR->CSR, PWR_CSR_BRE); +} + +/** + * @brief Disable the backup Regulator + * @rmtoll CSR BRE LL_PWR_DisableBkUpRegulator + * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. + * The LL_PWR_EnableBkUpAccess() must be called before using this API. + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableBkUpRegulator(void) +{ + CLEAR_BIT(PWR->CSR, PWR_CSR_BRE); +} + +/** + * @brief Check if the backup Regulator is enabled + * @rmtoll CSR BRE LL_PWR_IsEnabledBkUpRegulator + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpRegulator(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_BRE) == (PWR_CSR_BRE)); +} + +/** + * @brief Set voltage Regulator mode during deep sleep mode + * @rmtoll CR LPDS LL_PWR_SetRegulModeDS + * @param RegulMode This parameter can be one of the following values: + * @arg @ref LL_PWR_REGU_DSMODE_MAIN + * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER + * @retval None + */ +__STATIC_INLINE void LL_PWR_SetRegulModeDS(uint32_t RegulMode) +{ + MODIFY_REG(PWR->CR, PWR_CR_LPDS, RegulMode); +} + +/** + * @brief Get voltage Regulator mode during deep sleep mode + * @rmtoll CR LPDS LL_PWR_GetRegulModeDS + * @retval Returned value can be one of the following values: + * @arg @ref LL_PWR_REGU_DSMODE_MAIN + * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER + */ +__STATIC_INLINE uint32_t LL_PWR_GetRegulModeDS(void) +{ + return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_LPDS)); +} + +/** + * @brief Set Power Down mode when CPU enters deepsleep + * @rmtoll CR PDDS LL_PWR_SetPowerMode\n + * @rmtoll CR MRUDS LL_PWR_SetPowerMode\n + * @rmtoll CR LPUDS LL_PWR_SetPowerMode\n + * @rmtoll CR FPDS LL_PWR_SetPowerMode\n + * @rmtoll CR MRLVDS LL_PWR_SetPowerMode\n + * @rmtoll CR LPlVDS LL_PWR_SetPowerMode\n + * @rmtoll CR FPDS LL_PWR_SetPowerMode\n + * @rmtoll CR LPDS LL_PWR_SetPowerMode + * @param PDMode This parameter can be one of the following values: + * @arg @ref LL_PWR_MODE_STOP_MAINREGU + * @arg @ref LL_PWR_MODE_STOP_LPREGU + * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) + * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) + * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) + * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) + * + * (*) not available on all devices + * @arg @ref LL_PWR_MODE_STANDBY + * @retval None + */ +__STATIC_INLINE void LL_PWR_SetPowerMode(uint32_t PDMode) +{ +#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) + MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS), PDMode); +#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) + MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS), PDMode); +#else + MODIFY_REG(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS), PDMode); +#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ +} + +/** + * @brief Get Power Down mode when CPU enters deepsleep + * @rmtoll CR PDDS LL_PWR_GetPowerMode\n + * @rmtoll CR MRUDS LL_PWR_GetPowerMode\n + * @rmtoll CR LPUDS LL_PWR_GetPowerMode\n + * @rmtoll CR FPDS LL_PWR_GetPowerMode\n + * @rmtoll CR MRLVDS LL_PWR_GetPowerMode\n + * @rmtoll CR LPLVDS LL_PWR_GetPowerMode\n + * @rmtoll CR FPDS LL_PWR_GetPowerMode\n + * @rmtoll CR LPDS LL_PWR_GetPowerMode + * @retval Returned value can be one of the following values: + * @arg @ref LL_PWR_MODE_STOP_MAINREGU + * @arg @ref LL_PWR_MODE_STOP_LPREGU + * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) + * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) + * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) + * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) + * + * (*) not available on all devices + * @arg @ref LL_PWR_MODE_STANDBY + */ +__STATIC_INLINE uint32_t LL_PWR_GetPowerMode(void) +{ +#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) + return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS))); +#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) + return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS))); +#else + return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS))); +#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ +} + +/** + * @brief Configure the voltage threshold detected by the Power Voltage Detector + * @rmtoll CR PLS LL_PWR_SetPVDLevel + * @param PVDLevel This parameter can be one of the following values: + * @arg @ref LL_PWR_PVDLEVEL_0 + * @arg @ref LL_PWR_PVDLEVEL_1 + * @arg @ref LL_PWR_PVDLEVEL_2 + * @arg @ref LL_PWR_PVDLEVEL_3 + * @arg @ref LL_PWR_PVDLEVEL_4 + * @arg @ref LL_PWR_PVDLEVEL_5 + * @arg @ref LL_PWR_PVDLEVEL_6 + * @arg @ref LL_PWR_PVDLEVEL_7 + * @retval None + */ +__STATIC_INLINE void LL_PWR_SetPVDLevel(uint32_t PVDLevel) +{ + MODIFY_REG(PWR->CR, PWR_CR_PLS, PVDLevel); +} + +/** + * @brief Get the voltage threshold detection + * @rmtoll CR PLS LL_PWR_GetPVDLevel + * @retval Returned value can be one of the following values: + * @arg @ref LL_PWR_PVDLEVEL_0 + * @arg @ref LL_PWR_PVDLEVEL_1 + * @arg @ref LL_PWR_PVDLEVEL_2 + * @arg @ref LL_PWR_PVDLEVEL_3 + * @arg @ref LL_PWR_PVDLEVEL_4 + * @arg @ref LL_PWR_PVDLEVEL_5 + * @arg @ref LL_PWR_PVDLEVEL_6 + * @arg @ref LL_PWR_PVDLEVEL_7 + */ +__STATIC_INLINE uint32_t LL_PWR_GetPVDLevel(void) +{ + return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_PLS)); +} + +/** + * @brief Enable Power Voltage Detector + * @rmtoll CR PVDE LL_PWR_EnablePVD + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnablePVD(void) +{ + SET_BIT(PWR->CR, PWR_CR_PVDE); +} + +/** + * @brief Disable Power Voltage Detector + * @rmtoll CR PVDE LL_PWR_DisablePVD + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisablePVD(void) +{ + CLEAR_BIT(PWR->CR, PWR_CR_PVDE); +} + +/** + * @brief Check if Power Voltage Detector is enabled + * @rmtoll CR PVDE LL_PWR_IsEnabledPVD + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledPVD(void) +{ + return (READ_BIT(PWR->CR, PWR_CR_PVDE) == (PWR_CR_PVDE)); +} + +/** + * @brief Enable the WakeUp PINx functionality + * @rmtoll CSR EWUP LL_PWR_EnableWakeUpPin\n + * @rmtoll CSR EWUP1 LL_PWR_EnableWakeUpPin\n + * @rmtoll CSR EWUP2 LL_PWR_EnableWakeUpPin\n + * @rmtoll CSR EWUP3 LL_PWR_EnableWakeUpPin + * @param WakeUpPin This parameter can be one of the following values: + * @arg @ref LL_PWR_WAKEUP_PIN1 + * @arg @ref LL_PWR_WAKEUP_PIN2 (*) + * @arg @ref LL_PWR_WAKEUP_PIN3 (*) + * + * (*) not available on all devices + * @retval None + */ +__STATIC_INLINE void LL_PWR_EnableWakeUpPin(uint32_t WakeUpPin) +{ + SET_BIT(PWR->CSR, WakeUpPin); +} + +/** + * @brief Disable the WakeUp PINx functionality + * @rmtoll CSR EWUP LL_PWR_DisableWakeUpPin\n + * @rmtoll CSR EWUP1 LL_PWR_DisableWakeUpPin\n + * @rmtoll CSR EWUP2 LL_PWR_DisableWakeUpPin\n + * @rmtoll CSR EWUP3 LL_PWR_DisableWakeUpPin + * @param WakeUpPin This parameter can be one of the following values: + * @arg @ref LL_PWR_WAKEUP_PIN1 + * @arg @ref LL_PWR_WAKEUP_PIN2 (*) + * @arg @ref LL_PWR_WAKEUP_PIN3 (*) + * + * (*) not available on all devices + * @retval None + */ +__STATIC_INLINE void LL_PWR_DisableWakeUpPin(uint32_t WakeUpPin) +{ + CLEAR_BIT(PWR->CSR, WakeUpPin); +} + +/** + * @brief Check if the WakeUp PINx functionality is enabled + * @rmtoll CSR EWUP LL_PWR_IsEnabledWakeUpPin\n + * @rmtoll CSR EWUP1 LL_PWR_IsEnabledWakeUpPin\n + * @rmtoll CSR EWUP2 LL_PWR_IsEnabledWakeUpPin\n + * @rmtoll CSR EWUP3 LL_PWR_IsEnabledWakeUpPin + * @param WakeUpPin This parameter can be one of the following values: + * @arg @ref LL_PWR_WAKEUP_PIN1 + * @arg @ref LL_PWR_WAKEUP_PIN2 (*) + * @arg @ref LL_PWR_WAKEUP_PIN3 (*) + * + * (*) not available on all devices + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsEnabledWakeUpPin(uint32_t WakeUpPin) +{ + return (READ_BIT(PWR->CSR, WakeUpPin) == (WakeUpPin)); +} + + +/** + * @} + */ + +/** @defgroup PWR_LL_EF_FLAG_Management FLAG_Management + * @{ + */ + +/** + * @brief Get Wake-up Flag + * @rmtoll CSR WUF LL_PWR_IsActiveFlag_WU + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_WU(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_WUF) == (PWR_CSR_WUF)); +} + +/** + * @brief Get Standby Flag + * @rmtoll CSR SBF LL_PWR_IsActiveFlag_SB + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_SB(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_SBF) == (PWR_CSR_SBF)); +} + +/** + * @brief Get Backup Regulator ready Flag + * @rmtoll CSR BRR LL_PWR_IsActiveFlag_BRR + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_BRR(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_BRR) == (PWR_CSR_BRR)); +} +/** + * @brief Indicate whether VDD voltage is below the selected PVD threshold + * @rmtoll CSR PVDO LL_PWR_IsActiveFlag_PVDO + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_PVDO(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_PVDO) == (PWR_CSR_PVDO)); +} + +/** + * @brief Indicate whether the Regulator is ready in the selected voltage range or if its output voltage is still changing to the required voltage level + * @rmtoll CSR VOS LL_PWR_IsActiveFlag_VOS + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_VOS(void) +{ + return (READ_BIT(PWR->CSR, LL_PWR_CSR_VOS) == (LL_PWR_CSR_VOS)); +} +#if defined(PWR_CR_ODEN) +/** + * @brief Indicate whether the Over-Drive mode is ready or not + * @rmtoll CSR ODRDY LL_PWR_IsActiveFlag_OD + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_OD(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_ODRDY) == (PWR_CSR_ODRDY)); +} +#endif /* PWR_CR_ODEN */ + +#if defined(PWR_CR_ODSWEN) +/** + * @brief Indicate whether the Over-Drive mode switching is ready or not + * @rmtoll CSR ODSWRDY LL_PWR_IsActiveFlag_ODSW + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_ODSW(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_ODSWRDY) == (PWR_CSR_ODSWRDY)); +} +#endif /* PWR_CR_ODSWEN */ + +#if defined(PWR_CR_UDEN) +/** + * @brief Indicate whether the Under-Drive mode is ready or not + * @rmtoll CSR UDRDY LL_PWR_IsActiveFlag_UD + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_UD(void) +{ + return (READ_BIT(PWR->CSR, PWR_CSR_UDRDY) == (PWR_CSR_UDRDY)); +} +#endif /* PWR_CR_UDEN */ +/** + * @brief Clear Standby Flag + * @rmtoll CR CSBF LL_PWR_ClearFlag_SB + * @retval None + */ +__STATIC_INLINE void LL_PWR_ClearFlag_SB(void) +{ + SET_BIT(PWR->CR, PWR_CR_CSBF); +} + +/** + * @brief Clear Wake-up Flags + * @rmtoll CR CWUF LL_PWR_ClearFlag_WU + * @retval None + */ +__STATIC_INLINE void LL_PWR_ClearFlag_WU(void) +{ + SET_BIT(PWR->CR, PWR_CR_CWUF); +} +#if defined(PWR_CSR_UDRDY) +/** + * @brief Clear Under-Drive ready Flag + * @rmtoll CSR UDRDY LL_PWR_ClearFlag_UD + * @retval None + */ +__STATIC_INLINE void LL_PWR_ClearFlag_UD(void) +{ + WRITE_REG(PWR->CSR, PWR_CSR_UDRDY); +} +#endif /* PWR_CSR_UDRDY */ + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup PWR_LL_EF_Init De-initialization function + * @{ + */ +ErrorStatus LL_PWR_DeInit(void); +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(PWR) */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_PWR_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h index 1df1b58..1f2a91d 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h @@ -1,7096 +1,7096 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rcc.h - * @author MCD Application Team - * @brief Header file of RCC LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_RCC_H -#define __STM32F4xx_LL_RCC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup RCC_LL RCC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup RCC_LL_Private_Variables RCC Private Variables - * @{ - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -static const uint8_t aRCC_PLLSAIDIVRPrescTable[4] = {2, 4, 8, 16}; -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Private_Macros RCC Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Exported_Types RCC Exported Types - * @{ - */ - -/** @defgroup LL_ES_CLOCK_FREQ Clocks Frequency Structure - * @{ - */ - -/** - * @brief RCC Clocks Frequency Structure - */ -typedef struct -{ - uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency */ - uint32_t HCLK_Frequency; /*!< HCLK clock frequency */ - uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency */ - uint32_t PCLK2_Frequency; /*!< PCLK2 clock frequency */ -} LL_RCC_ClocksTypeDef; - -/** - * @} - */ - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_LL_EC_OSC_VALUES Oscillator Values adaptation - * @brief Defines used to adapt values of different oscillators - * @note These values could be modified in the user environment according to - * HW set-up. - * @{ - */ -#if !defined (HSE_VALUE) -#define HSE_VALUE 25000000U /*!< Value of the HSE oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSI_VALUE) -#define HSI_VALUE 16000000U /*!< Value of the HSI oscillator in Hz */ -#endif /* HSI_VALUE */ - -#if !defined (LSE_VALUE) -#define LSE_VALUE 32768U /*!< Value of the LSE oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSI_VALUE) -#define LSI_VALUE 32000U /*!< Value of the LSI oscillator in Hz */ -#endif /* LSI_VALUE */ - -#if !defined (EXTERNAL_CLOCK_VALUE) -#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the I2S_CKIN external oscillator in Hz */ -#endif /* EXTERNAL_CLOCK_VALUE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_RCC_WriteReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYC RCC_CIR_LSIRDYC /*!< LSI Ready Interrupt Clear */ -#define LL_RCC_CIR_LSERDYC RCC_CIR_LSERDYC /*!< LSE Ready Interrupt Clear */ -#define LL_RCC_CIR_HSIRDYC RCC_CIR_HSIRDYC /*!< HSI Ready Interrupt Clear */ -#define LL_RCC_CIR_HSERDYC RCC_CIR_HSERDYC /*!< HSE Ready Interrupt Clear */ -#define LL_RCC_CIR_PLLRDYC RCC_CIR_PLLRDYC /*!< PLL Ready Interrupt Clear */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYC RCC_CIR_PLLI2SRDYC /*!< PLLI2S Ready Interrupt Clear */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYC RCC_CIR_PLLSAIRDYC /*!< PLLSAI Ready Interrupt Clear */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSC RCC_CIR_CSSC /*!< Clock Security System Interrupt Clear */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RCC_ReadReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYF RCC_CIR_LSIRDYF /*!< LSI Ready Interrupt flag */ -#define LL_RCC_CIR_LSERDYF RCC_CIR_LSERDYF /*!< LSE Ready Interrupt flag */ -#define LL_RCC_CIR_HSIRDYF RCC_CIR_HSIRDYF /*!< HSI Ready Interrupt flag */ -#define LL_RCC_CIR_HSERDYF RCC_CIR_HSERDYF /*!< HSE Ready Interrupt flag */ -#define LL_RCC_CIR_PLLRDYF RCC_CIR_PLLRDYF /*!< PLL Ready Interrupt flag */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYF RCC_CIR_PLLI2SRDYF /*!< PLLI2S Ready Interrupt flag */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYF RCC_CIR_PLLSAIRDYF /*!< PLLSAI Ready Interrupt flag */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSF RCC_CIR_CSSF /*!< Clock Security System Interrupt flag */ -#define LL_RCC_CSR_LPWRRSTF RCC_CSR_LPWRRSTF /*!< Low-Power reset flag */ -#define LL_RCC_CSR_PINRSTF RCC_CSR_PINRSTF /*!< PIN reset flag */ -#define LL_RCC_CSR_PORRSTF RCC_CSR_PORRSTF /*!< POR/PDR reset flag */ -#define LL_RCC_CSR_SFTRSTF RCC_CSR_SFTRSTF /*!< Software Reset flag */ -#define LL_RCC_CSR_IWDGRSTF RCC_CSR_IWDGRSTF /*!< Independent Watchdog reset flag */ -#define LL_RCC_CSR_WWDGRSTF RCC_CSR_WWDGRSTF /*!< Window watchdog reset flag */ -#if defined(RCC_CSR_BORRSTF) -#define LL_RCC_CSR_BORRSTF RCC_CSR_BORRSTF /*!< BOR reset flag */ -#endif /* RCC_CSR_BORRSTF */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RCC_ReadReg and LL_RCC_WriteReg functions - * @{ - */ -#define LL_RCC_CIR_LSIRDYIE RCC_CIR_LSIRDYIE /*!< LSI Ready Interrupt Enable */ -#define LL_RCC_CIR_LSERDYIE RCC_CIR_LSERDYIE /*!< LSE Ready Interrupt Enable */ -#define LL_RCC_CIR_HSIRDYIE RCC_CIR_HSIRDYIE /*!< HSI Ready Interrupt Enable */ -#define LL_RCC_CIR_HSERDYIE RCC_CIR_HSERDYIE /*!< HSE Ready Interrupt Enable */ -#define LL_RCC_CIR_PLLRDYIE RCC_CIR_PLLRDYIE /*!< PLL Ready Interrupt Enable */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYIE RCC_CIR_PLLI2SRDYIE /*!< PLLI2S Ready Interrupt Enable */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYIE RCC_CIR_PLLSAIRDYIE /*!< PLLSAI Ready Interrupt Enable */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE System clock switch - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_PLL RCC_CFGR_SW_PLL /*!< PLL selection as system clock */ -#if defined(RCC_CFGR_SW_PLLR) -#define LL_RCC_SYS_CLKSOURCE_PLLR RCC_CFGR_SW_PLLR /*!< PLLR selection as system clock */ -#endif /* RCC_CFGR_SW_PLLR */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE_STATUS System clock switch status - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLL RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLLR RCC_CFGR_SWS_PLLR /*!< PLLR used as system clock */ -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYSCLK_DIV AHB prescaler - * @{ - */ -#define LL_RCC_SYSCLK_DIV_1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */ -#define LL_RCC_SYSCLK_DIV_2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */ -#define LL_RCC_SYSCLK_DIV_4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */ -#define LL_RCC_SYSCLK_DIV_8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */ -#define LL_RCC_SYSCLK_DIV_16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */ -#define LL_RCC_SYSCLK_DIV_64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */ -#define LL_RCC_SYSCLK_DIV_128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */ -#define LL_RCC_SYSCLK_DIV_256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */ -#define LL_RCC_SYSCLK_DIV_512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB1_DIV APB low-speed prescaler (APB1) - * @{ - */ -#define LL_RCC_APB1_DIV_1 RCC_CFGR_PPRE1_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB1_DIV_2 RCC_CFGR_PPRE1_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB1_DIV_4 RCC_CFGR_PPRE1_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB1_DIV_8 RCC_CFGR_PPRE1_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB1_DIV_16 RCC_CFGR_PPRE1_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB2_DIV APB high-speed prescaler (APB2) - * @{ - */ -#define LL_RCC_APB2_DIV_1 RCC_CFGR_PPRE2_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB2_DIV_2 RCC_CFGR_PPRE2_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB2_DIV_4 RCC_CFGR_PPRE2_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB2_DIV_8 RCC_CFGR_PPRE2_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB2_DIV_16 RCC_CFGR_PPRE2_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOxSOURCE MCO source selection - * @{ - */ -#define LL_RCC_MCO1SOURCE_HSI (uint32_t)(RCC_CFGR_MCO1|0x00000000U) /*!< HSI selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_LSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_0 >> 16U)) /*!< LSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_HSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_1 >> 16U)) /*!< HSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO1|((RCC_CFGR_MCO1_1|RCC_CFGR_MCO1_0) >> 16U)) /*!< PLLCLK selection as MCO1 source */ -#if defined(RCC_CFGR_MCO2) -#define LL_RCC_MCO2SOURCE_SYSCLK (uint32_t)(RCC_CFGR_MCO2|0x00000000U) /*!< SYSCLK selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLI2S (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_0 >> 16U)) /*!< PLLI2S selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_HSE (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_1 >> 16U)) /*!< HSE selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO2|((RCC_CFGR_MCO2_1|RCC_CFGR_MCO2_0) >> 16U)) /*!< PLLCLK selection as MCO2 source */ -#endif /* RCC_CFGR_MCO2 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOx_DIV MCO prescaler - * @{ - */ -#define LL_RCC_MCO1_DIV_1 (uint32_t)(RCC_CFGR_MCO1PRE|0x00000000U) /*!< MCO1 not divided */ -#define LL_RCC_MCO1_DIV_2 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE_2 >> 16U)) /*!< MCO1 divided by 2 */ -#define LL_RCC_MCO1_DIV_3 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_0) >> 16U)) /*!< MCO1 divided by 3 */ -#define LL_RCC_MCO1_DIV_4 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_1) >> 16U)) /*!< MCO1 divided by 4 */ -#define LL_RCC_MCO1_DIV_5 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE >> 16U)) /*!< MCO1 divided by 5 */ -#if defined(RCC_CFGR_MCO2PRE) -#define LL_RCC_MCO2_DIV_1 (uint32_t)(RCC_CFGR_MCO2PRE|0x00000000U) /*!< MCO2 not divided */ -#define LL_RCC_MCO2_DIV_2 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE_2 >> 16U)) /*!< MCO2 divided by 2 */ -#define LL_RCC_MCO2_DIV_3 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_0) >> 16U)) /*!< MCO2 divided by 3 */ -#define LL_RCC_MCO2_DIV_4 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_1) >> 16U)) /*!< MCO2 divided by 4 */ -#define LL_RCC_MCO2_DIV_5 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE >> 16U)) /*!< MCO2 divided by 5 */ -#endif /* RCC_CFGR_MCO2PRE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_RTC_HSEDIV HSE prescaler for RTC clock - * @{ - */ -#define LL_RCC_RTC_NOCLOCK 0x00000000U /*!< HSE not divided */ -#define LL_RCC_RTC_HSE_DIV_2 RCC_CFGR_RTCPRE_1 /*!< HSE clock divided by 2 */ -#define LL_RCC_RTC_HSE_DIV_3 (RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 3 */ -#define LL_RCC_RTC_HSE_DIV_4 RCC_CFGR_RTCPRE_2 /*!< HSE clock divided by 4 */ -#define LL_RCC_RTC_HSE_DIV_5 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 5 */ -#define LL_RCC_RTC_HSE_DIV_6 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 6 */ -#define LL_RCC_RTC_HSE_DIV_7 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 7 */ -#define LL_RCC_RTC_HSE_DIV_8 RCC_CFGR_RTCPRE_3 /*!< HSE clock divided by 8 */ -#define LL_RCC_RTC_HSE_DIV_9 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 9 */ -#define LL_RCC_RTC_HSE_DIV_10 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 10 */ -#define LL_RCC_RTC_HSE_DIV_11 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 11 */ -#define LL_RCC_RTC_HSE_DIV_12 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 12 */ -#define LL_RCC_RTC_HSE_DIV_13 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 13 */ -#define LL_RCC_RTC_HSE_DIV_14 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 14 */ -#define LL_RCC_RTC_HSE_DIV_15 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 15 */ -#define LL_RCC_RTC_HSE_DIV_16 RCC_CFGR_RTCPRE_4 /*!< HSE clock divided by 16 */ -#define LL_RCC_RTC_HSE_DIV_17 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 17 */ -#define LL_RCC_RTC_HSE_DIV_18 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 18 */ -#define LL_RCC_RTC_HSE_DIV_19 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 19 */ -#define LL_RCC_RTC_HSE_DIV_20 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 20 */ -#define LL_RCC_RTC_HSE_DIV_21 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 21 */ -#define LL_RCC_RTC_HSE_DIV_22 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 22 */ -#define LL_RCC_RTC_HSE_DIV_23 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 23 */ -#define LL_RCC_RTC_HSE_DIV_24 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3) /*!< HSE clock divided by 24 */ -#define LL_RCC_RTC_HSE_DIV_25 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 25 */ -#define LL_RCC_RTC_HSE_DIV_26 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 26 */ -#define LL_RCC_RTC_HSE_DIV_27 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 27 */ -#define LL_RCC_RTC_HSE_DIV_28 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 28 */ -#define LL_RCC_RTC_HSE_DIV_29 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 29 */ -#define LL_RCC_RTC_HSE_DIV_30 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 30 */ -#define LL_RCC_RTC_HSE_DIV_31 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 31 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EC_PERIPH_FREQUENCY Peripheral clock frequency - * @{ - */ -#define LL_RCC_PERIPH_FREQUENCY_NO 0x00000000U /*!< No clock enabled for the peripheral */ -#define LL_RCC_PERIPH_FREQUENCY_NA 0xFFFFFFFFU /*!< Frequency cannot be provided as external clock */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1_CLKSOURCE Peripheral FMPI2C clock source selection - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK RCC_DCKCFGR2_FMPI2C1SEL_0 /*!< SYSCLK clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_HSI RCC_DCKCFGR2_FMPI2C1SEL_1 /*!< HSI clock used as FMPI2C1 clock source */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1_CLKSOURCE Peripheral LPTIM clock source selection - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_HSI RCC_DCKCFGR2_LPTIM1SEL_0 /*!< LSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSI RCC_DCKCFGR2_LPTIM1SEL_1 /*!< HSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSE (uint32_t)(RCC_DCKCFGR2_LPTIM1SEL_1 | RCC_DCKCFGR2_LPTIM1SEL_0) /*!< LSE oscillator clock used as LPTIM1 clock */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx_CLKSOURCE Peripheral SAI clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1SRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_1 >> 16)) /*!< PLL clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC >> 16)) /*!< External pin clock used as SAI1 clock source */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI2SRC | 0x00000000U) /*!< PLLSAI clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_0 >> 16)) /*!< PLLI2S clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_1 >> 16)) /*!< PLL clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC >> 16)) /*!< PLL Main clock used as SAI2 clock source */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< External pin used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< PLL clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC >> 16)) /*!< PLL Main clock used as SAI1 block A clock source */ -#else -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< External pin clock used as SAI1 block A clock source */ -#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#if defined(RCC_SAI1B_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< External pin used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< PLL clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC >> 16)) /*!< PLL Main clock used as SAI1 block B clock source */ -#else -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< External pin clock used as SAI1 block B clock source */ -#endif /* RCC_SAI1B_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** @defgroup RCC_LL_EC_SDIOx_CLKSOURCE Peripheral SDIO clock source selection - * @{ - */ -#define LL_RCC_SDIO_CLKSOURCE_PLL48CLK 0x00000000U /*!< PLL 48M domain clock used as SDIO clock */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR_SDIOSEL /*!< System clock clock used as SDIO clock */ -#else -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR2_SDIOSEL /*!< System clock clock used as SDIO clock */ -#endif /* RCC_DCKCFGR_SDIOSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI_CLKSOURCE Peripheral DSI clock source selection - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE_PHY 0x00000000U /*!< DSI-PHY clock used as DSI byte lane clock source */ -#define LL_RCC_DSI_CLKSOURCE_PLL RCC_DCKCFGR_DSISEL /*!< PLL clock used as DSI byte lane clock source */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC_CLKSOURCE Peripheral CEC clock source selection - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE_HSI_DIV488 0x00000000U /*!< HSI oscillator clock divided by 488 used as CEC clock */ -#define LL_RCC_CEC_CLKSOURCE_LSE RCC_DCKCFGR2_CECSEL /*!< LSE oscillator clock used as CEC clock */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1_CLKSOURCE Peripheral I2S clock source selection - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S 0x00000000U /*!< I2S oscillator clock used as I2S1 clock */ -#define LL_RCC_I2S1_CLKSOURCE_PIN RCC_CFGR_I2SSRC /*!< External pin clock used as I2S1 clock */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2SSRC | 0x00000000U) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_1 >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S1SRC | 0x00000000U) /*!< PLLI2S clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_1 >> 16)) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S2SRC | 0x00000000U) /*!< PLLI2S clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_0 >> 16)) /*!< External pin used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_1 >> 16)) /*!< PLL clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC >> 16)) /*!< PLL Main clock used as I2S2 clock source */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M_CLKSOURCE Peripheral 48Mhz domain clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR2_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_CK48M_CLKSOURCE_PLLI2S RCC_DCKCFGR2_CK48MSEL /*!< PLLI2S oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG_CLKSOURCE Peripheral RNG clock source selection - * @{ - */ -#define LL_RCC_RNG_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as RNG clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_RNG_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as RNG clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_RNG_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as RNG clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB_CLKSOURCE Peripheral USB clock source selection - * @{ - */ -#define LL_RCC_USB_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as USB clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_USB_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as USB clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_USB_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as USB clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM1_AUDIO_CLKSOURCE Peripheral DFSDM Audio clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM1 Audio clock source */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | (RCC_DCKCFGR_CKDFSDM1ASEL << 16)) /*!< I2S2 clock used as DFSDM1 Audio clock source */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM2 Audio clock source */ -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | (RCC_DCKCFGR_CKDFSDM2ASEL << 16)) /*!< I2S2 clock used as DFSDM2 Audio clock source */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM1_CLKSOURCE Peripheral DFSDM clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM1 clock */ -#define LL_RCC_DFSDM1_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM1 clock */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM2 clock */ -#define LL_RCC_DFSDM2_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM2 clock */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1 Peripheral FMPI2C get clock source - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE RCC_DCKCFGR2_FMPI2C1SEL /*!< FMPI2C1 Clock source selection */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX_CLKSOURCE Peripheral SPDIFRX clock source selection - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLL 0x00000000U /*!< PLL clock used as SPDIFRX clock source */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S RCC_DCKCFGR2_SPDIFRXSEL /*!< PLLI2S clock used as SPDIFRX clock source */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1 Peripheral LPTIM get clock source - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE RCC_DCKCFGR2_LPTIM1SEL /*!< LPTIM1 Clock source selection */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx Peripheral SAI get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#define LL_RCC_SAI1_A_CLKSOURCE RCC_DCKCFGR_SAI1ASRC /*!< SAI1 block A Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#define LL_RCC_SAI1_B_CLKSOURCE RCC_DCKCFGR_SAI1BSRC /*!< SAI1 block B Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE RCC_DCKCFGR_SAI1SRC /*!< SAI1 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE RCC_DCKCFGR_SAI2SRC /*!< SAI2 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(SDIO) -/** @defgroup RCC_LL_EC_SDIOx Peripheral SDIO get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR_SDIOSEL /*!< SDIO Clock source selection */ -#elif defined(RCC_DCKCFGR2_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR2_SDIOSEL /*!< SDIO Clock source selection */ -#else -#define LL_RCC_SDIO_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< SDIO Clock source selection */ -#endif -/** - * @} - */ -#endif /* SDIO */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M Peripheral CK48M get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR2_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG Peripheral RNG get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_RNG_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< RNG Clock source selection */ -#else -#define LL_RCC_RNG_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< RNG Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB Peripheral USB get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_USB_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< USB Clock source selection */ -#else -#define LL_RCC_USB_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< USB Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC Peripheral CEC get clock source - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE RCC_DCKCFGR2_CECSEL /*!< CEC Clock source selection */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1 Peripheral I2S get clock source - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_CFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2S1SRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE RCC_DCKCFGR_I2S2SRC /*!< I2S2 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM_AUDIO Peripheral DFSDM Audio get clock source - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM1ASEL /*!< DFSDM1 Audio Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM2ASEL /*!< DFSDM2 Audio Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM Peripheral DFSDM get clock source - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM1 Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM2 Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX Peripheral SPDIFRX get clock source - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE RCC_DCKCFGR2_SPDIFRXSEL /*!< SPDIFRX Clock source selection */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI Peripheral DSI get clock source - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE RCC_DCKCFGR_DSISEL /*!< DSI Clock source selection */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(LTDC) -/** @defgroup RCC_LL_EC_LTDC Peripheral LTDC get clock source - * @{ - */ -#define LL_RCC_LTDC_CLKSOURCE RCC_DCKCFGR_PLLSAIDIVR /*!< LTDC Clock source selection */ -/** - * @} - */ -#endif /* LTDC */ - - -/** @defgroup RCC_LL_EC_RTC_CLKSOURCE RTC clock source selection - * @{ - */ -#define LL_RCC_RTC_CLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_HSE RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by HSE prescaler used as RTC clock */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EC_TIM_CLKPRESCALER Timers clocks prescalers selection - * @{ - */ -#define LL_RCC_TIM_PRESCALER_TWICE 0x00000000U /*!< Timers clock to twice PCLK */ -#define LL_RCC_TIM_PRESCALER_FOUR_TIMES RCC_DCKCFGR_TIMPRE /*!< Timers clock to four time PCLK */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EC_PLLSOURCE PLL, PLLI2S and PLLSAI entry clock source - * @{ - */ -#define LL_RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI /*!< HSI16 clock selected as PLL entry clock source */ -#define LL_RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE /*!< HSE clock selected as PLL entry clock source */ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) -#define LL_RCC_PLLI2SSOURCE_PIN (RCC_PLLI2SCFGR_PLLI2SSRC | 0x80U) /*!< I2S External pin input clock selected as PLLI2S entry clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLM_DIV PLL, PLLI2S and PLLSAI division factor - * @{ - */ -#define LL_RCC_PLLM_DIV_2 (RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 2 */ -#define LL_RCC_PLLM_DIV_3 (RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 3 */ -#define LL_RCC_PLLM_DIV_4 (RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 4 */ -#define LL_RCC_PLLM_DIV_5 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 5 */ -#define LL_RCC_PLLM_DIV_6 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 6 */ -#define LL_RCC_PLLM_DIV_7 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 7 */ -#define LL_RCC_PLLM_DIV_8 (RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 8 */ -#define LL_RCC_PLLM_DIV_9 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 9 */ -#define LL_RCC_PLLM_DIV_10 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 10 */ -#define LL_RCC_PLLM_DIV_11 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 11 */ -#define LL_RCC_PLLM_DIV_12 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 12 */ -#define LL_RCC_PLLM_DIV_13 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 13 */ -#define LL_RCC_PLLM_DIV_14 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 14 */ -#define LL_RCC_PLLM_DIV_15 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 15 */ -#define LL_RCC_PLLM_DIV_16 (RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 16 */ -#define LL_RCC_PLLM_DIV_17 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 17 */ -#define LL_RCC_PLLM_DIV_18 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 18 */ -#define LL_RCC_PLLM_DIV_19 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 19 */ -#define LL_RCC_PLLM_DIV_20 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 20 */ -#define LL_RCC_PLLM_DIV_21 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 21 */ -#define LL_RCC_PLLM_DIV_22 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 22 */ -#define LL_RCC_PLLM_DIV_23 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 23 */ -#define LL_RCC_PLLM_DIV_24 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 24 */ -#define LL_RCC_PLLM_DIV_25 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 25 */ -#define LL_RCC_PLLM_DIV_26 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 26 */ -#define LL_RCC_PLLM_DIV_27 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 27 */ -#define LL_RCC_PLLM_DIV_28 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 28 */ -#define LL_RCC_PLLM_DIV_29 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 29 */ -#define LL_RCC_PLLM_DIV_30 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 30 */ -#define LL_RCC_PLLM_DIV_31 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 31 */ -#define LL_RCC_PLLM_DIV_32 (RCC_PLLCFGR_PLLM_5) /*!< PLL, PLLI2S and PLLSAI division factor by 32 */ -#define LL_RCC_PLLM_DIV_33 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 33 */ -#define LL_RCC_PLLM_DIV_34 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 34 */ -#define LL_RCC_PLLM_DIV_35 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 35 */ -#define LL_RCC_PLLM_DIV_36 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 36 */ -#define LL_RCC_PLLM_DIV_37 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 37 */ -#define LL_RCC_PLLM_DIV_38 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 38 */ -#define LL_RCC_PLLM_DIV_39 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 39 */ -#define LL_RCC_PLLM_DIV_40 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 40 */ -#define LL_RCC_PLLM_DIV_41 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 41 */ -#define LL_RCC_PLLM_DIV_42 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 42 */ -#define LL_RCC_PLLM_DIV_43 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 43 */ -#define LL_RCC_PLLM_DIV_44 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 44 */ -#define LL_RCC_PLLM_DIV_45 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 45 */ -#define LL_RCC_PLLM_DIV_46 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 46 */ -#define LL_RCC_PLLM_DIV_47 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 47 */ -#define LL_RCC_PLLM_DIV_48 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 48 */ -#define LL_RCC_PLLM_DIV_49 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 49 */ -#define LL_RCC_PLLM_DIV_50 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 50 */ -#define LL_RCC_PLLM_DIV_51 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 51 */ -#define LL_RCC_PLLM_DIV_52 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 52 */ -#define LL_RCC_PLLM_DIV_53 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 53 */ -#define LL_RCC_PLLM_DIV_54 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 54 */ -#define LL_RCC_PLLM_DIV_55 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 55 */ -#define LL_RCC_PLLM_DIV_56 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 56 */ -#define LL_RCC_PLLM_DIV_57 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 57 */ -#define LL_RCC_PLLM_DIV_58 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 58 */ -#define LL_RCC_PLLM_DIV_59 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 59 */ -#define LL_RCC_PLLM_DIV_60 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 60 */ -#define LL_RCC_PLLM_DIV_61 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 61 */ -#define LL_RCC_PLLM_DIV_62 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 62 */ -#define LL_RCC_PLLM_DIV_63 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 63 */ -/** - * @} - */ - -#if defined(RCC_PLLCFGR_PLLR) -/** @defgroup RCC_LL_EC_PLLR_DIV PLL division factor (PLLR) - * @{ - */ -#define LL_RCC_PLLR_DIV_2 (RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 2 */ -#define LL_RCC_PLLR_DIV_3 (RCC_PLLCFGR_PLLR_1|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 3 */ -#define LL_RCC_PLLR_DIV_4 (RCC_PLLCFGR_PLLR_2) /*!< Main PLL division factor for PLLCLK (system clock) by 4 */ -#define LL_RCC_PLLR_DIV_5 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 5 */ -#define LL_RCC_PLLR_DIV_6 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 6 */ -#define LL_RCC_PLLR_DIV_7 (RCC_PLLCFGR_PLLR) /*!< Main PLL division factor for PLLCLK (system clock) by 7 */ -/** - * @} - */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** @defgroup RCC_LL_EC_PLLDIVR PLLDIVR division factor (PLLDIVR) - * @{ - */ -#define LL_RCC_PLLDIVR_DIV_1 (RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 1 */ -#define LL_RCC_PLLDIVR_DIV_2 (RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 2 */ -#define LL_RCC_PLLDIVR_DIV_3 (RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 3 */ -#define LL_RCC_PLLDIVR_DIV_4 (RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 4 */ -#define LL_RCC_PLLDIVR_DIV_5 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 5 */ -#define LL_RCC_PLLDIVR_DIV_6 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 6 */ -#define LL_RCC_PLLDIVR_DIV_7 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 7 */ -#define LL_RCC_PLLDIVR_DIV_8 (RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 8 */ -#define LL_RCC_PLLDIVR_DIV_9 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 9 */ -#define LL_RCC_PLLDIVR_DIV_10 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 10 */ -#define LL_RCC_PLLDIVR_DIV_11 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 11 */ -#define LL_RCC_PLLDIVR_DIV_12 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 12 */ -#define LL_RCC_PLLDIVR_DIV_13 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 13 */ -#define LL_RCC_PLLDIVR_DIV_14 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 14 */ -#define LL_RCC_PLLDIVR_DIV_15 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 15 */ -#define LL_RCC_PLLDIVR_DIV_16 (RCC_DCKCFGR_PLLDIVR_4) /*!< PLL division factor for PLLDIVR output by 16 */ -#define LL_RCC_PLLDIVR_DIV_17 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 17 */ -#define LL_RCC_PLLDIVR_DIV_18 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 18 */ -#define LL_RCC_PLLDIVR_DIV_19 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 19 */ -#define LL_RCC_PLLDIVR_DIV_20 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 20 */ -#define LL_RCC_PLLDIVR_DIV_21 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 21 */ -#define LL_RCC_PLLDIVR_DIV_22 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 22 */ -#define LL_RCC_PLLDIVR_DIV_23 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 23 */ -#define LL_RCC_PLLDIVR_DIV_24 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 24 */ -#define LL_RCC_PLLDIVR_DIV_25 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 25 */ -#define LL_RCC_PLLDIVR_DIV_26 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 26 */ -#define LL_RCC_PLLDIVR_DIV_27 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 27 */ -#define LL_RCC_PLLDIVR_DIV_28 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 28 */ -#define LL_RCC_PLLDIVR_DIV_29 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 29 */ -#define LL_RCC_PLLDIVR_DIV_30 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 30 */ -#define LL_RCC_PLLDIVR_DIV_31 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** @defgroup RCC_LL_EC_PLLP_DIV PLL division factor (PLLP) - * @{ - */ -#define LL_RCC_PLLP_DIV_2 0x00000000U /*!< Main PLL division factor for PLLP output by 2 */ -#define LL_RCC_PLLP_DIV_4 RCC_PLLCFGR_PLLP_0 /*!< Main PLL division factor for PLLP output by 4 */ -#define LL_RCC_PLLP_DIV_6 RCC_PLLCFGR_PLLP_1 /*!< Main PLL division factor for PLLP output by 6 */ -#define LL_RCC_PLLP_DIV_8 (RCC_PLLCFGR_PLLP_1 | RCC_PLLCFGR_PLLP_0) /*!< Main PLL division factor for PLLP output by 8 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLQ_DIV PLL division factor (PLLQ) - * @{ - */ -#define LL_RCC_PLLQ_DIV_2 RCC_PLLCFGR_PLLQ_1 /*!< Main PLL division factor for PLLQ output by 2 */ -#define LL_RCC_PLLQ_DIV_3 (RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 3 */ -#define LL_RCC_PLLQ_DIV_4 RCC_PLLCFGR_PLLQ_2 /*!< Main PLL division factor for PLLQ output by 4 */ -#define LL_RCC_PLLQ_DIV_5 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 5 */ -#define LL_RCC_PLLQ_DIV_6 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 6 */ -#define LL_RCC_PLLQ_DIV_7 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 7 */ -#define LL_RCC_PLLQ_DIV_8 RCC_PLLCFGR_PLLQ_3 /*!< Main PLL division factor for PLLQ output by 8 */ -#define LL_RCC_PLLQ_DIV_9 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 9 */ -#define LL_RCC_PLLQ_DIV_10 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 10 */ -#define LL_RCC_PLLQ_DIV_11 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 11 */ -#define LL_RCC_PLLQ_DIV_12 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2) /*!< Main PLL division factor for PLLQ output by 12 */ -#define LL_RCC_PLLQ_DIV_13 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 13 */ -#define LL_RCC_PLLQ_DIV_14 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 14 */ -#define LL_RCC_PLLQ_DIV_15 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 15 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLL_SPRE_SEL PLL Spread Spectrum Selection - * @{ - */ -#define LL_RCC_SPREAD_SELECT_CENTER 0x00000000U /*!< PLL center spread spectrum selection */ -#define LL_RCC_SPREAD_SELECT_DOWN RCC_SSCGR_SPREADSEL /*!< PLL down spread spectrum selection */ -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EC_PLLI2SM PLLI2SM division factor (PLLI2SM) - * @{ - */ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) -#define LL_RCC_PLLI2SM_DIV_2 (RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 (RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 (RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 (RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 (RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 (RCC_PLLI2SCFGR_PLLI2SM_5) /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#else -#define LL_RCC_PLLI2SM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** @defgroup RCC_LL_EC_PLLI2SQ PLLI2SQ division factor (PLLI2SQ) - * @{ - */ -#define LL_RCC_PLLI2SQ_DIV_2 RCC_PLLI2SCFGR_PLLI2SQ_1 /*!< PLLI2S division factor for PLLI2SQ output by 2 */ -#define LL_RCC_PLLI2SQ_DIV_3 (RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 3 */ -#define LL_RCC_PLLI2SQ_DIV_4 RCC_PLLI2SCFGR_PLLI2SQ_2 /*!< PLLI2S division factor for PLLI2SQ output by 4 */ -#define LL_RCC_PLLI2SQ_DIV_5 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 5 */ -#define LL_RCC_PLLI2SQ_DIV_6 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 6 */ -#define LL_RCC_PLLI2SQ_DIV_7 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 7 */ -#define LL_RCC_PLLI2SQ_DIV_8 RCC_PLLI2SCFGR_PLLI2SQ_3 /*!< PLLI2S division factor for PLLI2SQ output by 8 */ -#define LL_RCC_PLLI2SQ_DIV_9 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 9 */ -#define LL_RCC_PLLI2SQ_DIV_10 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 10 */ -#define LL_RCC_PLLI2SQ_DIV_11 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 11 */ -#define LL_RCC_PLLI2SQ_DIV_12 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2) /*!< PLLI2S division factor for PLLI2SQ output by 12 */ -#define LL_RCC_PLLI2SQ_DIV_13 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 13 */ -#define LL_RCC_PLLI2SQ_DIV_14 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 14 */ -#define LL_RCC_PLLI2SQ_DIV_15 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 15 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** @defgroup RCC_LL_EC_PLLI2SDIVQ PLLI2SDIVQ division factor (PLLI2SDIVQ) - * @{ - */ -#define LL_RCC_PLLI2SDIVQ_DIV_1 0x00000000U /*!< PLLI2S division factor for PLLI2SDIVQ output by 1 */ -#define LL_RCC_PLLI2SDIVQ_DIV_2 RCC_DCKCFGR_PLLI2SDIVQ_0 /*!< PLLI2S division factor for PLLI2SDIVQ output by 2 */ -#define LL_RCC_PLLI2SDIVQ_DIV_3 RCC_DCKCFGR_PLLI2SDIVQ_1 /*!< PLLI2S division factor for PLLI2SDIVQ output by 3 */ -#define LL_RCC_PLLI2SDIVQ_DIV_4 (RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 4 */ -#define LL_RCC_PLLI2SDIVQ_DIV_5 RCC_DCKCFGR_PLLI2SDIVQ_2 /*!< PLLI2S division factor for PLLI2SDIVQ output by 5 */ -#define LL_RCC_PLLI2SDIVQ_DIV_6 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 6 */ -#define LL_RCC_PLLI2SDIVQ_DIV_7 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 7 */ -#define LL_RCC_PLLI2SDIVQ_DIV_8 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 8 */ -#define LL_RCC_PLLI2SDIVQ_DIV_9 RCC_DCKCFGR_PLLI2SDIVQ_3 /*!< PLLI2S division factor for PLLI2SDIVQ output by 9 */ -#define LL_RCC_PLLI2SDIVQ_DIV_10 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 10 */ -#define LL_RCC_PLLI2SDIVQ_DIV_11 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 11 */ -#define LL_RCC_PLLI2SDIVQ_DIV_12 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 12 */ -#define LL_RCC_PLLI2SDIVQ_DIV_13 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 13 */ -#define LL_RCC_PLLI2SDIVQ_DIV_14 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 14 */ -#define LL_RCC_PLLI2SDIVQ_DIV_15 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 15 */ -#define LL_RCC_PLLI2SDIVQ_DIV_16 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 16 */ -#define LL_RCC_PLLI2SDIVQ_DIV_17 RCC_DCKCFGR_PLLI2SDIVQ_4 /*!< PLLI2S division factor for PLLI2SDIVQ output by 17 */ -#define LL_RCC_PLLI2SDIVQ_DIV_18 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 18 */ -#define LL_RCC_PLLI2SDIVQ_DIV_19 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 19 */ -#define LL_RCC_PLLI2SDIVQ_DIV_20 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 20 */ -#define LL_RCC_PLLI2SDIVQ_DIV_21 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 21 */ -#define LL_RCC_PLLI2SDIVQ_DIV_22 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 22 */ -#define LL_RCC_PLLI2SDIVQ_DIV_23 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 23 */ -#define LL_RCC_PLLI2SDIVQ_DIV_24 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 24 */ -#define LL_RCC_PLLI2SDIVQ_DIV_25 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3) /*!< PLLI2S division factor for PLLI2SDIVQ output by 25 */ -#define LL_RCC_PLLI2SDIVQ_DIV_26 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 26 */ -#define LL_RCC_PLLI2SDIVQ_DIV_27 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 27 */ -#define LL_RCC_PLLI2SDIVQ_DIV_28 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 28 */ -#define LL_RCC_PLLI2SDIVQ_DIV_29 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 29 */ -#define LL_RCC_PLLI2SDIVQ_DIV_30 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 30 */ -#define LL_RCC_PLLI2SDIVQ_DIV_31 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 31 */ -#define LL_RCC_PLLI2SDIVQ_DIV_32 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** @defgroup RCC_LL_EC_PLLI2SDIVR PLLI2SDIVR division factor (PLLI2SDIVR) - * @{ - */ -#define LL_RCC_PLLI2SDIVR_DIV_1 (RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 1 */ -#define LL_RCC_PLLI2SDIVR_DIV_2 (RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 2 */ -#define LL_RCC_PLLI2SDIVR_DIV_3 (RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 3 */ -#define LL_RCC_PLLI2SDIVR_DIV_4 (RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 4 */ -#define LL_RCC_PLLI2SDIVR_DIV_5 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 5 */ -#define LL_RCC_PLLI2SDIVR_DIV_6 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 6 */ -#define LL_RCC_PLLI2SDIVR_DIV_7 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 7 */ -#define LL_RCC_PLLI2SDIVR_DIV_8 (RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 8 */ -#define LL_RCC_PLLI2SDIVR_DIV_9 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 9 */ -#define LL_RCC_PLLI2SDIVR_DIV_10 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 10 */ -#define LL_RCC_PLLI2SDIVR_DIV_11 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 11 */ -#define LL_RCC_PLLI2SDIVR_DIV_12 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 12 */ -#define LL_RCC_PLLI2SDIVR_DIV_13 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 13 */ -#define LL_RCC_PLLI2SDIVR_DIV_14 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 14 */ -#define LL_RCC_PLLI2SDIVR_DIV_15 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 15 */ -#define LL_RCC_PLLI2SDIVR_DIV_16 (RCC_DCKCFGR_PLLI2SDIVR_4) /*!< PLLI2S division factor for PLLI2SDIVR output by 16 */ -#define LL_RCC_PLLI2SDIVR_DIV_17 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 17 */ -#define LL_RCC_PLLI2SDIVR_DIV_18 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 18 */ -#define LL_RCC_PLLI2SDIVR_DIV_19 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 19 */ -#define LL_RCC_PLLI2SDIVR_DIV_20 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 20 */ -#define LL_RCC_PLLI2SDIVR_DIV_21 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 21 */ -#define LL_RCC_PLLI2SDIVR_DIV_22 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 22 */ -#define LL_RCC_PLLI2SDIVR_DIV_23 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 23 */ -#define LL_RCC_PLLI2SDIVR_DIV_24 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 24 */ -#define LL_RCC_PLLI2SDIVR_DIV_25 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 25 */ -#define LL_RCC_PLLI2SDIVR_DIV_26 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 26 */ -#define LL_RCC_PLLI2SDIVR_DIV_27 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 27 */ -#define LL_RCC_PLLI2SDIVR_DIV_28 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 28 */ -#define LL_RCC_PLLI2SDIVR_DIV_29 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 29 */ -#define LL_RCC_PLLI2SDIVR_DIV_30 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 30 */ -#define LL_RCC_PLLI2SDIVR_DIV_31 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** @defgroup RCC_LL_EC_PLLI2SR PLLI2SR division factor (PLLI2SR) - * @{ - */ -#define LL_RCC_PLLI2SR_DIV_2 RCC_PLLI2SCFGR_PLLI2SR_1 /*!< PLLI2S division factor for PLLI2SR output by 2 */ -#define LL_RCC_PLLI2SR_DIV_3 (RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 3 */ -#define LL_RCC_PLLI2SR_DIV_4 RCC_PLLI2SCFGR_PLLI2SR_2 /*!< PLLI2S division factor for PLLI2SR output by 4 */ -#define LL_RCC_PLLI2SR_DIV_5 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 5 */ -#define LL_RCC_PLLI2SR_DIV_6 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1) /*!< PLLI2S division factor for PLLI2SR output by 6 */ -#define LL_RCC_PLLI2SR_DIV_7 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 7 */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** @defgroup RCC_LL_EC_PLLI2SP PLLI2SP division factor (PLLI2SP) - * @{ - */ -#define LL_RCC_PLLI2SP_DIV_2 0x00000000U /*!< PLLI2S division factor for PLLI2SP output by 2 */ -#define LL_RCC_PLLI2SP_DIV_4 RCC_PLLI2SCFGR_PLLI2SP_0 /*!< PLLI2S division factor for PLLI2SP output by 4 */ -#define LL_RCC_PLLI2SP_DIV_6 RCC_PLLI2SCFGR_PLLI2SP_1 /*!< PLLI2S division factor for PLLI2SP output by 6 */ -#define LL_RCC_PLLI2SP_DIV_8 (RCC_PLLI2SCFGR_PLLI2SP_1 | RCC_PLLI2SCFGR_PLLI2SP_0) /*!< PLLI2S division factor for PLLI2SP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EC_PLLSAIM PLLSAIM division factor (PLLSAIM or PLLM) - * @{ - */ -#if defined(RCC_PLLSAICFGR_PLLSAIM) -#define LL_RCC_PLLSAIM_DIV_2 (RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 (RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 (RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 (RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 (RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 (RCC_PLLSAICFGR_PLLSAIM_5) /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#else -#define LL_RCC_PLLSAIM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLSAIQ PLLSAIQ division factor (PLLSAIQ) - * @{ - */ -#define LL_RCC_PLLSAIQ_DIV_2 RCC_PLLSAICFGR_PLLSAIQ_1 /*!< PLLSAI division factor for PLLSAIQ output by 2 */ -#define LL_RCC_PLLSAIQ_DIV_3 (RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 3 */ -#define LL_RCC_PLLSAIQ_DIV_4 RCC_PLLSAICFGR_PLLSAIQ_2 /*!< PLLSAI division factor for PLLSAIQ output by 4 */ -#define LL_RCC_PLLSAIQ_DIV_5 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 5 */ -#define LL_RCC_PLLSAIQ_DIV_6 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 6 */ -#define LL_RCC_PLLSAIQ_DIV_7 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 7 */ -#define LL_RCC_PLLSAIQ_DIV_8 RCC_PLLSAICFGR_PLLSAIQ_3 /*!< PLLSAI division factor for PLLSAIQ output by 8 */ -#define LL_RCC_PLLSAIQ_DIV_9 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 9 */ -#define LL_RCC_PLLSAIQ_DIV_10 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 10 */ -#define LL_RCC_PLLSAIQ_DIV_11 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 11 */ -#define LL_RCC_PLLSAIQ_DIV_12 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2) /*!< PLLSAI division factor for PLLSAIQ output by 12 */ -#define LL_RCC_PLLSAIQ_DIV_13 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 13 */ -#define LL_RCC_PLLSAIQ_DIV_14 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 14 */ -#define LL_RCC_PLLSAIQ_DIV_15 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 15 */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVQ) -/** @defgroup RCC_LL_EC_PLLSAIDIVQ PLLSAIDIVQ division factor (PLLSAIDIVQ) - * @{ - */ -#define LL_RCC_PLLSAIDIVQ_DIV_1 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVQ output by 1 */ -#define LL_RCC_PLLSAIDIVQ_DIV_2 RCC_DCKCFGR_PLLSAIDIVQ_0 /*!< PLLSAI division factor for PLLSAIDIVQ output by 2 */ -#define LL_RCC_PLLSAIDIVQ_DIV_3 RCC_DCKCFGR_PLLSAIDIVQ_1 /*!< PLLSAI division factor for PLLSAIDIVQ output by 3 */ -#define LL_RCC_PLLSAIDIVQ_DIV_4 (RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 4 */ -#define LL_RCC_PLLSAIDIVQ_DIV_5 RCC_DCKCFGR_PLLSAIDIVQ_2 /*!< PLLSAI division factor for PLLSAIDIVQ output by 5 */ -#define LL_RCC_PLLSAIDIVQ_DIV_6 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 6 */ -#define LL_RCC_PLLSAIDIVQ_DIV_7 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 7 */ -#define LL_RCC_PLLSAIDIVQ_DIV_8 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 8 */ -#define LL_RCC_PLLSAIDIVQ_DIV_9 RCC_DCKCFGR_PLLSAIDIVQ_3 /*!< PLLSAI division factor for PLLSAIDIVQ output by 9 */ -#define LL_RCC_PLLSAIDIVQ_DIV_10 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 10 */ -#define LL_RCC_PLLSAIDIVQ_DIV_11 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 11 */ -#define LL_RCC_PLLSAIDIVQ_DIV_12 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 12 */ -#define LL_RCC_PLLSAIDIVQ_DIV_13 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 13 */ -#define LL_RCC_PLLSAIDIVQ_DIV_14 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 14 */ -#define LL_RCC_PLLSAIDIVQ_DIV_15 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 15 */ -#define LL_RCC_PLLSAIDIVQ_DIV_16 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 16 */ -#define LL_RCC_PLLSAIDIVQ_DIV_17 RCC_DCKCFGR_PLLSAIDIVQ_4 /*!< PLLSAI division factor for PLLSAIDIVQ output by 17 */ -#define LL_RCC_PLLSAIDIVQ_DIV_18 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 18 */ -#define LL_RCC_PLLSAIDIVQ_DIV_19 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 19 */ -#define LL_RCC_PLLSAIDIVQ_DIV_20 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 20 */ -#define LL_RCC_PLLSAIDIVQ_DIV_21 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 21 */ -#define LL_RCC_PLLSAIDIVQ_DIV_22 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 22 */ -#define LL_RCC_PLLSAIDIVQ_DIV_23 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 23 */ -#define LL_RCC_PLLSAIDIVQ_DIV_24 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 24 */ -#define LL_RCC_PLLSAIDIVQ_DIV_25 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3) /*!< PLLSAI division factor for PLLSAIDIVQ output by 25 */ -#define LL_RCC_PLLSAIDIVQ_DIV_26 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 26 */ -#define LL_RCC_PLLSAIDIVQ_DIV_27 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 27 */ -#define LL_RCC_PLLSAIDIVQ_DIV_28 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 28 */ -#define LL_RCC_PLLSAIDIVQ_DIV_29 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 29 */ -#define LL_RCC_PLLSAIDIVQ_DIV_30 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 30 */ -#define LL_RCC_PLLSAIDIVQ_DIV_31 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 31 */ -#define LL_RCC_PLLSAIDIVQ_DIV_32 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVQ */ - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** @defgroup RCC_LL_EC_PLLSAIR PLLSAIR division factor (PLLSAIR) - * @{ - */ -#define LL_RCC_PLLSAIR_DIV_2 RCC_PLLSAICFGR_PLLSAIR_1 /*!< PLLSAI division factor for PLLSAIR output by 2 */ -#define LL_RCC_PLLSAIR_DIV_3 (RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 3 */ -#define LL_RCC_PLLSAIR_DIV_4 RCC_PLLSAICFGR_PLLSAIR_2 /*!< PLLSAI division factor for PLLSAIR output by 4 */ -#define LL_RCC_PLLSAIR_DIV_5 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 5 */ -#define LL_RCC_PLLSAIR_DIV_6 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1) /*!< PLLSAI division factor for PLLSAIR output by 6 */ -#define LL_RCC_PLLSAIR_DIV_7 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 7 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** @defgroup RCC_LL_EC_PLLSAIDIVR PLLSAIDIVR division factor (PLLSAIDIVR) - * @{ - */ -#define LL_RCC_PLLSAIDIVR_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVR output by 2 */ -#define LL_RCC_PLLSAIDIVR_DIV_4 RCC_DCKCFGR_PLLSAIDIVR_0 /*!< PLLSAI division factor for PLLSAIDIVR output by 4 */ -#define LL_RCC_PLLSAIDIVR_DIV_8 RCC_DCKCFGR_PLLSAIDIVR_1 /*!< PLLSAI division factor for PLLSAIDIVR output by 8 */ -#define LL_RCC_PLLSAIDIVR_DIV_16 (RCC_DCKCFGR_PLLSAIDIVR_1 | RCC_DCKCFGR_PLLSAIDIVR_0) /*!< PLLSAI division factor for PLLSAIDIVR output by 16 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** @defgroup RCC_LL_EC_PLLSAIP PLLSAIP division factor (PLLSAIP) - * @{ - */ -#define LL_RCC_PLLSAIP_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIP output by 2 */ -#define LL_RCC_PLLSAIP_DIV_4 RCC_PLLSAICFGR_PLLSAIP_0 /*!< PLLSAI division factor for PLLSAIP output by 4 */ -#define LL_RCC_PLLSAIP_DIV_6 RCC_PLLSAICFGR_PLLSAIP_1 /*!< PLLSAI division factor for PLLSAIP output by 6 */ -#define LL_RCC_PLLSAIP_DIV_8 (RCC_PLLSAICFGR_PLLSAIP_1 | RCC_PLLSAICFGR_PLLSAIP_0) /*!< PLLSAI division factor for PLLSAIP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RCC register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RCC_WriteReg(__REG__, __VALUE__) WRITE_REG(RCC->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RCC register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RCC_ReadReg(__REG__) READ_REG(RCC->__REG__) -/** - * @} - */ - -/** @defgroup RCC_LL_EM_CALC_FREQ Calculate frequencies - * @{ - */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLP__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((((__PLLP__) >> RCC_PLLCFGR_PLLP_Pos ) + 1U) * 2U)) - -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -/** - * @brief Helper macro to calculate the PLLRCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLRCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLRCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) - -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency used on 48M domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLQ__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLQ__) >> RCC_PLLCFGR_PLLQ_Pos )) - -#if defined(DSI) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on DSI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_DSI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_DSI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on I2S - * @note ex: @ref __LL_RCC_CALC_PLLCLK_I2S_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SPDIFRX - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SAI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SAI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR (), @ref LL_RCC_PLL_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param __PLLDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLL clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__, __PLLDIVR__) (((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) / ((__PLLDIVR__) >> RCC_DCKCFGR_PLLDIVR_Pos )) -#else -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_DCKCFGR_PLLDIVR */ -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetQ (), @ref LL_RCC_PLLSAI_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param __PLLSAIDIVQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIQ__, __PLLSAIDIVQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIQ__) >> RCC_PLLSAICFGR_PLLSAIQ_Pos) * (((__PLLSAIDIVQ__) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos) + 1U))) - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Helper macro to calculate the PLLSAI frequency used on 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 50 and 432 - * @param __PLLSAIP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - ((((__PLLSAIP__) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) * 2U)) -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for LTDC domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_LTDC_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetR (), @ref LL_RCC_PLLSAI_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param __PLLSAIDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_LTDC_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIR__, __PLLSAIDIVR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIR__) >> RCC_PLLSAICFGR_PLLSAIR_Pos) * (aRCC_PLLSAIDIVRPrescTable[(__PLLSAIDIVR__) >> RCC_DCKCFGR_PLLSAIDIVR_Pos]))) -#endif /* LTDC */ -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2S_SUPPORT) -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ (), @ref LL_RCC_PLLI2S_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param __PLLI2SDIVQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLLI2S clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos) * (((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos) + 1U))) -#else -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos) * ((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVR_Pos))) - -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ || RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLI2S frequency used on SPDIFRX domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((((__PLLI2SP__) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) * 2U)) - -#endif /* SPDIFRX */ - -/** - * @brief Helper macro to calculate the PLLI2S frequency used for I2S domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_I2S_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SR__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos)) - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SQ__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos)) - -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_PLLI2S_SUPPORT */ - -/** - * @brief Helper macro to calculate the HCLK frequency - * @param __SYSCLKFREQ__ SYSCLK frequency (based on HSE/HSI/PLLCLK) - * @param __AHBPRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval HCLK clock frequency (in Hz) - */ -#define __LL_RCC_CALC_HCLK_FREQ(__SYSCLKFREQ__, __AHBPRESCALER__) ((__SYSCLKFREQ__) >> AHBPrescTable[((__AHBPRESCALER__) & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos]) - -/** - * @brief Helper macro to calculate the PCLK1 frequency (ABP1) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB1PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval PCLK1 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK1_FREQ(__HCLKFREQ__, __APB1PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB1PRESCALER__) >> RCC_CFGR_PPRE1_Pos]) - -/** - * @brief Helper macro to calculate the PCLK2 frequency (ABP2) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB2PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval PCLK2 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK2_FREQ(__HCLKFREQ__, __APB2PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB2PRESCALER__) >> RCC_CFGR_PPRE2_Pos]) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Functions RCC Exported Functions - * @{ - */ - -/** @defgroup RCC_LL_EF_HSE HSE - * @{ - */ - -/** - * @brief Enable the Clock Security System. - * @rmtoll CR CSSON LL_RCC_HSE_EnableCSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableCSS(void) -{ - SET_BIT(RCC->CR, RCC_CR_CSSON); -} - -/** - * @brief Enable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableBypass(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Disable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Enable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Disable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Check if HSE oscillator Ready - * @rmtoll CR HSERDY LL_RCC_HSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSE_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSERDY) == (RCC_CR_HSERDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_HSI HSI - * @{ - */ - -/** - * @brief Enable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Disable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Check if HSI clock is ready - * @rmtoll CR HSIRDY LL_RCC_HSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == (RCC_CR_HSIRDY)); -} - -/** - * @brief Get HSI Calibration value - * @note When HSITRIM is written, HSICAL is updated with the sum of - * HSITRIM and the factory trim value - * @rmtoll CR HSICAL LL_RCC_HSI_GetCalibration - * @retval Between Min_Data = 0x00 and Max_Data = 0xFF - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibration(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSICAL) >> RCC_CR_HSICAL_Pos); -} - -/** - * @brief Set HSI Calibration trimming - * @note user-programmable trimming value that is added to the HSICAL - * @note Default value is 16, which, when added to the HSICAL value, - * should trim the HSI to 16 MHz +/- 1 % - * @rmtoll CR HSITRIM LL_RCC_HSI_SetCalibTrimming - * @param Value Between Min_Data = 0 and Max_Data = 31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_SetCalibTrimming(uint32_t Value) -{ - MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, Value << RCC_CR_HSITRIM_Pos); -} - -/** - * @brief Get HSI Calibration trimming - * @rmtoll CR HSITRIM LL_RCC_HSI_GetCalibTrimming - * @retval Between Min_Data = 0 and Max_Data = 31 - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibTrimming(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSE LSE - * @{ - */ - -/** - * @brief Enable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Enable(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Disable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Disable(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Enable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableBypass(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Disable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Check if LSE oscillator Ready - * @rmtoll BDCR LSERDY LL_RCC_LSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSE_IsReady(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == (RCC_BDCR_LSERDY)); -} - -#if defined(RCC_BDCR_LSEMOD) -/** - * @brief Enable LSE high drive mode. - * @note LSE high drive mode can be enabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_EnableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableHighDriveMode(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} - -/** - * @brief Disable LSE high drive mode. - * @note LSE high drive mode can be disabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_DisableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableHighDriveMode(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} -#endif /* RCC_BDCR_LSEMOD */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSI LSI - * @{ - */ - -/** - * @brief Enable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Enable(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Disable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Disable(void) -{ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Check if LSI is Ready - * @rmtoll CSR LSIRDY LL_RCC_LSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSI_IsReady(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == (RCC_CSR_LSIRDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_System System - * @{ - */ - -/** - * @brief Configure the system clock source - * @rmtoll CFGR SW LL_RCC_SetSysClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLLR (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSysClkSource(uint32_t Source) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, Source); -} - -/** - * @brief Get the system clock source - * @rmtoll CFGR SWS LL_RCC_GetSysClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLLR (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSysClkSource(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_SWS)); -} - -/** - * @brief Set AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_SetAHBPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAHBPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, Prescaler); -} - -/** - * @brief Set APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_SetAPB1Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB1Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, Prescaler); -} - -/** - * @brief Set APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_SetAPB2Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB2Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, Prescaler); -} - -/** - * @brief Get AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_GetAHBPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAHBPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_HPRE)); -} - -/** - * @brief Get APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_GetAPB1Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB1Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1)); -} - -/** - * @brief Get APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_GetAPB2Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB2Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_MCO MCO - * @{ - */ - -#if defined(RCC_CFGR_MCO1EN) -/** - * @brief Enable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} - -/** - * @brief Disable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} -#endif /* RCC_CFGR_MCO1EN */ - -#if defined(RCC_CFGR_MCO2EN) -/** - * @brief Enable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} - -/** - * @brief Disable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} -#endif /* RCC_CFGR_MCO2EN */ - -/** - * @brief Configure MCOx - * @rmtoll CFGR MCO1 LL_RCC_ConfigMCO\n - * CFGR MCO1PRE LL_RCC_ConfigMCO\n - * CFGR MCO2 LL_RCC_ConfigMCO\n - * CFGR MCO2PRE LL_RCC_ConfigMCO - * @param MCOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1SOURCE_HSI - * @arg @ref LL_RCC_MCO1SOURCE_LSE - * @arg @ref LL_RCC_MCO1SOURCE_HSE - * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK - * @arg @ref LL_RCC_MCO2SOURCE_SYSCLK - * @arg @ref LL_RCC_MCO2SOURCE_PLLI2S - * @arg @ref LL_RCC_MCO2SOURCE_HSE - * @arg @ref LL_RCC_MCO2SOURCE_PLLCLK - * @param MCOxPrescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1_DIV_1 - * @arg @ref LL_RCC_MCO1_DIV_2 - * @arg @ref LL_RCC_MCO1_DIV_3 - * @arg @ref LL_RCC_MCO1_DIV_4 - * @arg @ref LL_RCC_MCO1_DIV_5 - * @arg @ref LL_RCC_MCO2_DIV_1 - * @arg @ref LL_RCC_MCO2_DIV_2 - * @arg @ref LL_RCC_MCO2_DIV_3 - * @arg @ref LL_RCC_MCO2_DIV_4 - * @arg @ref LL_RCC_MCO2_DIV_5 - * @retval None - */ -__STATIC_INLINE void LL_RCC_ConfigMCO(uint32_t MCOxSource, uint32_t MCOxPrescaler) -{ - MODIFY_REG(RCC->CFGR, (MCOxSource & 0xFFFF0000U) | (MCOxPrescaler & 0xFFFF0000U), (MCOxSource << 16U) | (MCOxPrescaler << 16U)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Peripheral_Clock_Source Peripheral Clock Source - * @{ - */ -#if defined(FMPI2C1) -/** - * @brief Configure FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_SetFMPI2CClockSource - * @param FMPI2CxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetFMPI2CClockSource(uint32_t FMPI2CxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, FMPI2CxSource); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Configure LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_SetLPTIMClockSource - * @param LPTIMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetLPTIMClockSource(uint32_t LPTIMxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, LPTIMxSource); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Configure SAIx clock source - * @rmtoll DCKCFGR SAI1SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI2SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_SetSAIClockSource - * @param SAIxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSAIClockSource(uint32_t SAIxSource) -{ - MODIFY_REG(RCC->DCKCFGR, (SAIxSource & 0xFFFF0000U), (SAIxSource << 16U)); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Configure SDIO clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_SetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_SetSDIOClockSource - * @param SDIOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSDIOClockSource(uint32_t SDIOxSource) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, SDIOxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, SDIOxSource); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Configure 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetCK48MClockSource - * @param CK48MxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCK48MClockSource(uint32_t CK48MxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, CK48MxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, CK48MxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Configure RNG clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetRNGClockSource - * @param RNGxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRNGClockSource(uint32_t RNGxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, RNGxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, RNGxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Configure USB clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetUSBClockSource - * @param USBxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetUSBClockSource(uint32_t USBxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, USBxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, USBxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Configure CEC clock source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_SetCECClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCECClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, Source); -} -#endif /* CEC */ - -/** - * @brief Configure I2S clock source - * @rmtoll CFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_SetI2SClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetI2SClockSource(uint32_t Source) -{ -#if defined(RCC_CFGR_I2SSRC) - MODIFY_REG(RCC->CFGR, RCC_CFGR_I2SSRC, Source); -#else - MODIFY_REG(RCC->DCKCFGR, (Source & 0xFFFF0000U), (Source << 16U)); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DSI) -/** - * @brief Configure DSI clock source - * @rmtoll DCKCFGR DSISEL LL_RCC_SetDSIClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDSIClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, Source); -} -#endif /* DSI */ - -#if defined(DFSDM1_Channel0) -/** - * @brief Configure DFSDM Audio clock source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_SetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_SetDFSDMAudioClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMAudioClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, (Source & 0x0000FFFFU), (Source >> 16U)); -} - -/** - * @brief Configure DFSDM Kernel clock source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_SetDFSDMClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, Source); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Configure SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_SetSPDIFRXClockSource - * @param SPDIFRXxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSPDIFRXClockSource(uint32_t SPDIFRXxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, SPDIFRXxSource); -} -#endif /* SPDIFRX */ - -#if defined(FMPI2C1) -/** - * @brief Get FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_GetFMPI2CClockSource - * @param FMPI2Cx This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - */ -__STATIC_INLINE uint32_t LL_RCC_GetFMPI2CClockSource(uint32_t FMPI2Cx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, FMPI2Cx)); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Get LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_GetLPTIMClockSource - * @param LPTIMx This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetLPTIMClockSource(uint32_t LPTIMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Get SAIx clock source - * @rmtoll DCKCFGR SAI1SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI2SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_GetSAIClockSource - * @param SAIx This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSAIClockSource(uint32_t SAIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SAIx) >> 16U | SAIx); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Get SDIOx clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_GetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_GetSDIOClockSource - * @param SDIOx This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - */ -__STATIC_INLINE uint32_t LL_RCC_GetSDIOClockSource(uint32_t SDIOx) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SDIOx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SDIOx)); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Get 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetCK48MClockSource - * @param CK48Mx This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetCK48MClockSource(uint32_t CK48Mx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, CK48Mx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CK48Mx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Get RNGx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetRNGClockSource - * @param RNGx This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetRNGClockSource(uint32_t RNGx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RNGx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RNGx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Get USBx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetUSBClockSource - * @param USBx This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetUSBClockSource(uint32_t USBx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, USBx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, USBx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Get CEC Clock Source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_GetCECClockSource - * @param CECx This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetCECClockSource(uint32_t CECx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CECx)); -} -#endif /* CEC */ - -/** - * @brief Get I2S Clock Source - * @rmtoll CFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_GetI2SClockSource - * @param I2Sx This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE - * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetI2SClockSource(uint32_t I2Sx) -{ -#if defined(RCC_CFGR_I2SSRC) - return (uint32_t)(READ_BIT(RCC->CFGR, I2Sx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR, I2Sx) >> 16U | I2Sx); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DFSDM1_Channel0) -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_GetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_GetDFSDMAudioClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMAudioClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx) << 16U | DFSDMx); -} - -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_GetDFSDMClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx)); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Get SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_GetSPDIFRXClockSource - * @param SPDIFRXx This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSPDIFRXClockSource(uint32_t SPDIFRXx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SPDIFRXx)); -} -#endif /* SPDIFRX */ - -#if defined(DSI) -/** - * @brief Get DSI Clock Source - * @rmtoll DCKCFGR DSISEL LL_RCC_GetDSIClockSource - * @param DSIx This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - */ -__STATIC_INLINE uint32_t LL_RCC_GetDSIClockSource(uint32_t DSIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DSIx)); -} -#endif /* DSI */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_RTC RTC - * @{ - */ - -/** - * @brief Set RTC Clock Source - * @note Once the RTC clock source has been selected, it cannot be changed anymore unless - * the Backup domain is reset, or unless a failure is detected on LSE (LSECSSD is - * set). The BDRST bit can be used to reset them. - * @rmtoll BDCR RTCSEL LL_RCC_SetRTCClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTCClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, Source); -} - -/** - * @brief Get RTC Clock Source - * @rmtoll BDCR RTCSEL LL_RCC_GetRTCClockSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTCClockSource(void) -{ - return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)); -} - -/** - * @brief Enable RTC - * @rmtoll BDCR RTCEN LL_RCC_EnableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableRTC(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Disable RTC - * @rmtoll BDCR RTCEN LL_RCC_DisableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableRTC(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Check if RTC has been enabled or not - * @rmtoll BDCR RTCEN LL_RCC_IsEnabledRTC - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledRTC(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_RTCEN) == (RCC_BDCR_RTCEN)); -} - -/** - * @brief Force the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ForceBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ForceBackupDomainReset(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Release the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ReleaseBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ReleaseBackupDomainReset(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Set HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_SetRTC_HSEPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTC_HSEPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, Prescaler); -} - -/** - * @brief Get HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_GetRTC_HSEPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTC_HSEPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE)); -} - -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EF_TIM_CLOCK_PRESCALER TIM - * @{ - */ - -/** - * @brief Set Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_SetTIMPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetTIMPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE, Prescaler); -} - -/** - * @brief Get Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_GetTIMPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - */ -__STATIC_INLINE uint32_t LL_RCC_GetTIMPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE)); -} - -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EF_PLL PLL - * @{ - */ - -/** - * @brief Enable PLL - * @rmtoll CR PLLON LL_RCC_PLL_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Disable PLL - * @note Cannot be disabled if the PLL clock is used as the system clock - * @rmtoll CR PLLON LL_RCC_PLL_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Check if PLL Ready - * @rmtoll CR PLLRDY LL_RCC_PLL_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == (RCC_CR_PLLRDY)); -} - -/** - * @brief Configure PLL used for SYSCLK Domain - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLL is disabled - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLP LL_RCC_PLL_ConfigDomain_SYS - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLP_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @arg @ref LL_RCC_PLLR_DIV_2 (*) - * @arg @ref LL_RCC_PLLR_DIV_3 (*) - * @arg @ref LL_RCC_PLLR_DIV_4 (*) - * @arg @ref LL_RCC_PLLR_DIV_5 (*) - * @arg @ref LL_RCC_PLLR_DIV_6 (*) - * @arg @ref LL_RCC_PLLR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP_R) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos); - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLP, PLLP_R); -#if defined(RCC_PLLR_SYSCLK_SUPPORT) - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLR, PLLP_R); -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -} - -/** - * @brief Configure PLL used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLL is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLQ LL_RCC_PLL_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLQ, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLQ); -} - -#if defined(DSI) -/** - * @brief Configure PLL used for DSI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for DSI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_DSI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_DSI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Configure PLL used for I2S clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLL used for SPDIFRX clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Configure PLL used for SAI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SAI\n - * DCKCFGR PLLDIVR LL_RCC_PLL_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -#else -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -#endif /* RCC_DCKCFGR_PLLDIVR */ -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -#if defined(RCC_DCKCFGR_PLLDIVR) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, PLLDIVR); -#endif /* RCC_DCKCFGR_PLLDIVR */ -} -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -/** - * @brief Configure PLL clock source - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_SetMainSource - * @param PLLSource This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SetMainSource(uint32_t PLLSource) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, PLLSource); -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetMainSource(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -} - -/** - * @brief Get Main PLL multiplication factor for VCO - * @rmtoll PLLCFGR PLLN LL_RCC_PLL_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); -} - -/** - * @brief Get Main PLL division factor for PLLP - * @rmtoll PLLCFGR PLLP LL_RCC_PLL_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLP)); -} - -/** - * @brief Get Main PLL division factor for PLLQ - * @note used for PLL48MCLK selected for USB, RNG, SDIO (48 MHz clock) - * @rmtoll PLLCFGR PLLQ LL_RCC_PLL_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ)); -} - -#if defined(RCC_PLLCFGR_PLLR) -/** - * @brief Get Main PLL division factor for PLLR - * @note used for PLLCLK (system clock) - * @rmtoll PLLCFGR PLLR LL_RCC_PLL_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR)); -} -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** - * @brief Get Main PLL division factor for PLLDIVR - * @note used for PLLSAICLK (SAI1 and SAI2 clock) - * @rmtoll DCKCFGR PLLDIVR LL_RCC_PLL_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 - * @arg @ref LL_RCC_PLLDIVR_DIV_2 - * @arg @ref LL_RCC_PLLDIVR_DIV_3 - * @arg @ref LL_RCC_PLLDIVR_DIV_4 - * @arg @ref LL_RCC_PLLDIVR_DIV_5 - * @arg @ref LL_RCC_PLLDIVR_DIV_6 - * @arg @ref LL_RCC_PLLDIVR_DIV_7 - * @arg @ref LL_RCC_PLLDIVR_DIV_8 - * @arg @ref LL_RCC_PLLDIVR_DIV_9 - * @arg @ref LL_RCC_PLLDIVR_DIV_10 - * @arg @ref LL_RCC_PLLDIVR_DIV_11 - * @arg @ref LL_RCC_PLLDIVR_DIV_12 - * @arg @ref LL_RCC_PLLDIVR_DIV_13 - * @arg @ref LL_RCC_PLLDIVR_DIV_14 - * @arg @ref LL_RCC_PLLDIVR_DIV_15 - * @arg @ref LL_RCC_PLLDIVR_DIV_16 - * @arg @ref LL_RCC_PLLDIVR_DIV_17 - * @arg @ref LL_RCC_PLLDIVR_DIV_18 - * @arg @ref LL_RCC_PLLDIVR_DIV_19 - * @arg @ref LL_RCC_PLLDIVR_DIV_20 - * @arg @ref LL_RCC_PLLDIVR_DIV_21 - * @arg @ref LL_RCC_PLLDIVR_DIV_22 - * @arg @ref LL_RCC_PLLDIVR_DIV_23 - * @arg @ref LL_RCC_PLLDIVR_DIV_24 - * @arg @ref LL_RCC_PLLDIVR_DIV_25 - * @arg @ref LL_RCC_PLLDIVR_DIV_26 - * @arg @ref LL_RCC_PLLDIVR_DIV_27 - * @arg @ref LL_RCC_PLLDIVR_DIV_28 - * @arg @ref LL_RCC_PLLDIVR_DIV_29 - * @arg @ref LL_RCC_PLLDIVR_DIV_30 - * @arg @ref LL_RCC_PLLDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR)); -} -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** - * @brief Get Division factor for the main PLL and other PLL - * @rmtoll PLLCFGR PLLM LL_RCC_PLL_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDivider(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -} - -/** - * @brief Configure Spread Spectrum used for PLL - * @note These bits must be written before enabling PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR INCSTEP LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR SPREADSEL LL_RCC_PLL_ConfigSpreadSpectrum - * @param Mod Between Min_Data=0 and Max_Data=8191 - * @param Inc Between Min_Data=0 and Max_Data=32767 - * @param Sel This parameter can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigSpreadSpectrum(uint32_t Mod, uint32_t Inc, uint32_t Sel) -{ - MODIFY_REG(RCC->SSCGR, RCC_SSCGR_MODPER | RCC_SSCGR_INCSTEP | RCC_SSCGR_SPREADSEL, Mod | (Inc << RCC_SSCGR_INCSTEP_Pos) | Sel); -} - -/** - * @brief Get Spread Spectrum Modulation Period for PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_GetPeriodModulation - * @retval Between Min_Data=0 and Max_Data=8191 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetPeriodModulation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_MODPER)); -} - -/** - * @brief Get Spread Spectrum Incrementation Step for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR INCSTEP LL_RCC_PLL_GetStepIncrementation - * @retval Between Min_Data=0 and Max_Data=32767 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetStepIncrementation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_INCSTEP) >> RCC_SSCGR_INCSTEP_Pos); -} - -/** - * @brief Get Spread Spectrum Selection for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR SPREADSEL LL_RCC_PLL_GetSpreadSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetSpreadSelection(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_SPREADSEL)); -} - -/** - * @brief Enable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Enable(void) -{ - SET_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @brief Disable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Disable(void) -{ - CLEAR_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EF_PLLI2S PLLI2S - * @{ - */ - -/** - * @brief Enable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Disable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Check if PLLI2S Ready - * @rmtoll CR PLLI2SRDY LL_RCC_PLLI2S_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) == (RCC_CR_PLLI2SRDY)); -} - -#if (defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR)) -/** - * @brief Configure PLLI2S used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param PLLDIVQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ_R, uint32_t PLLDIVQ_R) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos); -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, PLLDIVQ_R); -#else - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, PLLDIVQ_R); -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ && RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Configure PLLI2S used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLI2S is disabled - * @note This can be selected for RNG, USB, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SQ, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLQ); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLLI2S used for SPDIFRX domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLI2S is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SP, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLP); -} -#endif /* SPDIFRX */ - -/** - * @brief Configure PLLI2S used for I2S1 domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SR, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLR); -} - -/** - * @brief Get I2SPLL multiplication factor for VCO - * @rmtoll PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** - * @brief Get I2SPLL division factor for PLLI2SQ - * @rmtoll PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -/** - * @brief Get I2SPLL division factor for PLLI2SR - * @note used for PLLI2SCLK (I2S clock) - * @rmtoll PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR)); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** - * @brief Get I2SPLL division factor for PLLI2SP - * @note used for PLLSPDIFRXCLK (SPDIFRX clock) - * @rmtoll PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SP)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVR - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** - * @brief Get division factor for PLLI2S input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLI2S_GetDivider\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDivider(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_GetMainSource\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetMainSource(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - uint32_t pllsrc = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC); - uint32_t plli2sssrc0 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC); - uint32_t plli2sssrc1 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC) >> 15U; - return (uint32_t)(pllsrc | plli2sssrc0 | plli2sssrc1); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -} - -/** - * @} - */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EF_PLLSAI PLLSAI - * @{ - */ - -/** - * @brief Enable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Disable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Check if PLLSAI Ready - * @rmtoll CR PLLSAIRDY LL_RCC_PLLSAI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) == (RCC_CR_PLLSAIRDY)); -} - -/** - * @brief Configure PLLSAI used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLSAI is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_ConfigDomain_SAI\n - * DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param PLLDIVQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ, uint32_t PLLDIVQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIQ, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLQ); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, PLLDIVQ); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Configure PLLSAI used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLSAI is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIP, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLP); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Configure PLLSAI used for LTDC domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLSAI is disabled - * @note This can be selected for LTDC - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_ConfigDomain_LTDC - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_LTDC(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM, Source | PLLM); - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIR, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLR); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, PLLDIVR); -} -#endif /* LTDC */ - -/** - * @brief Get division factor for PLLSAI input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLSAI_GetDivider\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDivider(void) -{ -#if defined(RCC_PLLSAICFGR_PLLSAIM) - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -} - -/** - * @brief Get SAIPLL multiplication factor for VCO - * @rmtoll PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_GetN - * @retval Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); -} - -/** - * @brief Get SAIPLL division factor for PLLSAIQ - * @rmtoll PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIQ)); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** - * @brief Get SAIPLL division factor for PLLSAIR - * @note used for PLLSAICLK (SAI clock) - * @rmtoll PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIR)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Get SAIPLL division factor for PLLSAIP - * @note used for PLL48MCLK (48M domain clock) - * @rmtoll PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIP)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -/** - * @brief Get SAIPLL division factor for PLLSAIDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ)); -} - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** - * @brief Get SAIPLL division factor for PLLSAIDIVR - * @note used for LTDC domain clock - * @rmtoll DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR)); -} -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -#endif /* RCC_PLLSAI_SUPPORT */ - -/** @defgroup RCC_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Clear LSI ready interrupt flag - * @rmtoll CIR LSIRDYC LL_RCC_ClearFlag_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC); -} - -/** - * @brief Clear LSE ready interrupt flag - * @rmtoll CIR LSERDYC LL_RCC_ClearFlag_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYC); -} - -/** - * @brief Clear HSI ready interrupt flag - * @rmtoll CIR HSIRDYC LL_RCC_ClearFlag_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYC); -} - -/** - * @brief Clear HSE ready interrupt flag - * @rmtoll CIR HSERDYC LL_RCC_ClearFlag_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYC); -} - -/** - * @brief Clear PLL ready interrupt flag - * @rmtoll CIR PLLRDYC LL_RCC_ClearFlag_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYC); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Clear PLLI2S ready interrupt flag - * @rmtoll CIR PLLI2SRDYC LL_RCC_ClearFlag_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Clear PLLSAI ready interrupt flag - * @rmtoll CIR PLLSAIRDYC LL_RCC_ClearFlag_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -} - -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Clear Clock security system interrupt flag - * @rmtoll CIR CSSC LL_RCC_ClearFlag_HSECSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSECSS(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_CSSC); -} - -/** - * @brief Check if LSI ready interrupt occurred or not - * @rmtoll CIR LSIRDYF LL_RCC_IsActiveFlag_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYF) == (RCC_CIR_LSIRDYF)); -} - -/** - * @brief Check if LSE ready interrupt occurred or not - * @rmtoll CIR LSERDYF LL_RCC_IsActiveFlag_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYF) == (RCC_CIR_LSERDYF)); -} - -/** - * @brief Check if HSI ready interrupt occurred or not - * @rmtoll CIR HSIRDYF LL_RCC_IsActiveFlag_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYF) == (RCC_CIR_HSIRDYF)); -} - -/** - * @brief Check if HSE ready interrupt occurred or not - * @rmtoll CIR HSERDYF LL_RCC_IsActiveFlag_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYF) == (RCC_CIR_HSERDYF)); -} - -/** - * @brief Check if PLL ready interrupt occurred or not - * @rmtoll CIR PLLRDYF LL_RCC_IsActiveFlag_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYF) == (RCC_CIR_PLLRDYF)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Check if PLLI2S ready interrupt occurred or not - * @rmtoll CIR PLLI2SRDYF LL_RCC_IsActiveFlag_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYF) == (RCC_CIR_PLLI2SRDYF)); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Check if PLLSAI ready interrupt occurred or not - * @rmtoll CIR PLLSAIRDYF LL_RCC_IsActiveFlag_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYF) == (RCC_CIR_PLLSAIRDYF)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Check if Clock security system interrupt occurred or not - * @rmtoll CIR CSSF LL_RCC_IsActiveFlag_HSECSS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSECSS(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_CSSF) == (RCC_CIR_CSSF)); -} - -/** - * @brief Check if RCC flag Independent Watchdog reset is set or not. - * @rmtoll CSR IWDGRSTF LL_RCC_IsActiveFlag_IWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_IWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_IWDGRSTF) == (RCC_CSR_IWDGRSTF)); -} - -/** - * @brief Check if RCC flag Low Power reset is set or not. - * @rmtoll CSR LPWRRSTF LL_RCC_IsActiveFlag_LPWRRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LPWRRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LPWRRSTF) == (RCC_CSR_LPWRRSTF)); -} - -/** - * @brief Check if RCC flag Pin reset is set or not. - * @rmtoll CSR PINRSTF LL_RCC_IsActiveFlag_PINRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PINRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PINRSTF) == (RCC_CSR_PINRSTF)); -} - -/** - * @brief Check if RCC flag POR/PDR reset is set or not. - * @rmtoll CSR PORRSTF LL_RCC_IsActiveFlag_PORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PORRSTF) == (RCC_CSR_PORRSTF)); -} - -/** - * @brief Check if RCC flag Software reset is set or not. - * @rmtoll CSR SFTRSTF LL_RCC_IsActiveFlag_SFTRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_SFTRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_SFTRSTF) == (RCC_CSR_SFTRSTF)); -} - -/** - * @brief Check if RCC flag Window Watchdog reset is set or not. - * @rmtoll CSR WWDGRSTF LL_RCC_IsActiveFlag_WWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_WWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_WWDGRSTF) == (RCC_CSR_WWDGRSTF)); -} - -#if defined(RCC_CSR_BORRSTF) -/** - * @brief Check if RCC flag BOR reset is set or not. - * @rmtoll CSR BORRSTF LL_RCC_IsActiveFlag_BORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_BORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_BORRSTF) == (RCC_CSR_BORRSTF)); -} -#endif /* RCC_CSR_BORRSTF */ - -/** - * @brief Set RMVF bit to clear the reset flags. - * @rmtoll CSR RMVF LL_RCC_ClearResetFlags - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearResetFlags(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_IT_Management IT Management - * @{ - */ - -/** - * @brief Enable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_EnableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Enable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_EnableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Enable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_EnableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Enable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_EnableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Enable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_EnableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Enable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_EnableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Enable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_EnableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Disable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_DisableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Disable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_DisableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Disable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_DisableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Disable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_DisableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Disable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_DisableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Disable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_DisableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLI2SRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Disable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_DisableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLSAIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Checks if LSI ready interrupt source is enabled or disabled. - * @rmtoll CIR LSIRDYIE LL_RCC_IsEnabledIT_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYIE) == (RCC_CIR_LSIRDYIE)); -} - -/** - * @brief Checks if LSE ready interrupt source is enabled or disabled. - * @rmtoll CIR LSERDYIE LL_RCC_IsEnabledIT_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYIE) == (RCC_CIR_LSERDYIE)); -} - -/** - * @brief Checks if HSI ready interrupt source is enabled or disabled. - * @rmtoll CIR HSIRDYIE LL_RCC_IsEnabledIT_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYIE) == (RCC_CIR_HSIRDYIE)); -} - -/** - * @brief Checks if HSE ready interrupt source is enabled or disabled. - * @rmtoll CIR HSERDYIE LL_RCC_IsEnabledIT_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYIE) == (RCC_CIR_HSERDYIE)); -} - -/** - * @brief Checks if PLL ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLRDYIE LL_RCC_IsEnabledIT_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYIE) == (RCC_CIR_PLLRDYIE)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Checks if PLLI2S ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLI2SRDYIE LL_RCC_IsEnabledIT_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE) == (RCC_CIR_PLLI2SRDYIE)); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Checks if PLLSAI ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLSAIRDYIE LL_RCC_IsEnabledIT_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE) == (RCC_CIR_PLLSAIRDYIE)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_RCC_DeInit(void); -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Get_Freq Get system and peripherals clocks frequency functions - * @{ - */ -void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks); -#if defined(FMPI2C1) -uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource); -#endif /* FMPI2C1 */ -#if defined(LPTIM1) -uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource); -#endif /* LPTIM1 */ -#if defined(SAI1) -uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource); -#endif /* SAI1 */ -#if defined(SDIO) -uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource); -#endif /* SDIO */ -#if defined(RNG) -uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource); -#endif /* RNG */ -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource); -#endif /* USB_OTG_FS || USB_OTG_HS */ -#if defined(DFSDM1_Channel0) -uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource); -uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource); -#endif /* DFSDM1_Channel0 */ -uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource); -#if defined(CEC) -uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource); -#endif /* CEC */ -#if defined(LTDC) -uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource); -#endif /* LTDC */ -#if defined(SPDIFRX) -uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource); -#endif /* SPDIFRX */ -#if defined(DSI) -uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource); -#endif /* DSI */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RCC_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_rcc.h + * @author MCD Application Team + * @brief Header file of RCC LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_RCC_H +#define __STM32F4xx_LL_RCC_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(RCC) + +/** @defgroup RCC_LL RCC + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup RCC_LL_Private_Variables RCC Private Variables + * @{ + */ + +#if defined(RCC_DCKCFGR_PLLSAIDIVR) +static const uint8_t aRCC_PLLSAIDIVRPrescTable[4] = {2, 4, 8, 16}; +#endif /* RCC_DCKCFGR_PLLSAIDIVR */ + +/** + * @} + */ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup RCC_LL_Private_Macros RCC Private Macros + * @{ + */ +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup RCC_LL_Exported_Types RCC Exported Types + * @{ + */ + +/** @defgroup LL_ES_CLOCK_FREQ Clocks Frequency Structure + * @{ + */ + +/** + * @brief RCC Clocks Frequency Structure + */ +typedef struct +{ + uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency */ + uint32_t HCLK_Frequency; /*!< HCLK clock frequency */ + uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency */ + uint32_t PCLK2_Frequency; /*!< PCLK2 clock frequency */ +} LL_RCC_ClocksTypeDef; + +/** + * @} + */ + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup RCC_LL_Exported_Constants RCC Exported Constants + * @{ + */ + +/** @defgroup RCC_LL_EC_OSC_VALUES Oscillator Values adaptation + * @brief Defines used to adapt values of different oscillators + * @note These values could be modified in the user environment according to + * HW set-up. + * @{ + */ +#if !defined (HSE_VALUE) +#define HSE_VALUE 25000000U /*!< Value of the HSE oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) +#define HSI_VALUE 16000000U /*!< Value of the HSI oscillator in Hz */ +#endif /* HSI_VALUE */ + +#if !defined (LSE_VALUE) +#define LSE_VALUE 32768U /*!< Value of the LSE oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSI_VALUE) +#define LSI_VALUE 32000U /*!< Value of the LSI oscillator in Hz */ +#endif /* LSI_VALUE */ + +#if !defined (EXTERNAL_CLOCK_VALUE) +#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the I2S_CKIN external oscillator in Hz */ +#endif /* EXTERNAL_CLOCK_VALUE */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_CLEAR_FLAG Clear Flags Defines + * @brief Flags defines which can be used with LL_RCC_WriteReg function + * @{ + */ +#define LL_RCC_CIR_LSIRDYC RCC_CIR_LSIRDYC /*!< LSI Ready Interrupt Clear */ +#define LL_RCC_CIR_LSERDYC RCC_CIR_LSERDYC /*!< LSE Ready Interrupt Clear */ +#define LL_RCC_CIR_HSIRDYC RCC_CIR_HSIRDYC /*!< HSI Ready Interrupt Clear */ +#define LL_RCC_CIR_HSERDYC RCC_CIR_HSERDYC /*!< HSE Ready Interrupt Clear */ +#define LL_RCC_CIR_PLLRDYC RCC_CIR_PLLRDYC /*!< PLL Ready Interrupt Clear */ +#if defined(RCC_PLLI2S_SUPPORT) +#define LL_RCC_CIR_PLLI2SRDYC RCC_CIR_PLLI2SRDYC /*!< PLLI2S Ready Interrupt Clear */ +#endif /* RCC_PLLI2S_SUPPORT */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_CIR_PLLSAIRDYC RCC_CIR_PLLSAIRDYC /*!< PLLSAI Ready Interrupt Clear */ +#endif /* RCC_PLLSAI_SUPPORT */ +#define LL_RCC_CIR_CSSC RCC_CIR_CSSC /*!< Clock Security System Interrupt Clear */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_RCC_ReadReg function + * @{ + */ +#define LL_RCC_CIR_LSIRDYF RCC_CIR_LSIRDYF /*!< LSI Ready Interrupt flag */ +#define LL_RCC_CIR_LSERDYF RCC_CIR_LSERDYF /*!< LSE Ready Interrupt flag */ +#define LL_RCC_CIR_HSIRDYF RCC_CIR_HSIRDYF /*!< HSI Ready Interrupt flag */ +#define LL_RCC_CIR_HSERDYF RCC_CIR_HSERDYF /*!< HSE Ready Interrupt flag */ +#define LL_RCC_CIR_PLLRDYF RCC_CIR_PLLRDYF /*!< PLL Ready Interrupt flag */ +#if defined(RCC_PLLI2S_SUPPORT) +#define LL_RCC_CIR_PLLI2SRDYF RCC_CIR_PLLI2SRDYF /*!< PLLI2S Ready Interrupt flag */ +#endif /* RCC_PLLI2S_SUPPORT */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_CIR_PLLSAIRDYF RCC_CIR_PLLSAIRDYF /*!< PLLSAI Ready Interrupt flag */ +#endif /* RCC_PLLSAI_SUPPORT */ +#define LL_RCC_CIR_CSSF RCC_CIR_CSSF /*!< Clock Security System Interrupt flag */ +#define LL_RCC_CSR_LPWRRSTF RCC_CSR_LPWRRSTF /*!< Low-Power reset flag */ +#define LL_RCC_CSR_PINRSTF RCC_CSR_PINRSTF /*!< PIN reset flag */ +#define LL_RCC_CSR_PORRSTF RCC_CSR_PORRSTF /*!< POR/PDR reset flag */ +#define LL_RCC_CSR_SFTRSTF RCC_CSR_SFTRSTF /*!< Software Reset flag */ +#define LL_RCC_CSR_IWDGRSTF RCC_CSR_IWDGRSTF /*!< Independent Watchdog reset flag */ +#define LL_RCC_CSR_WWDGRSTF RCC_CSR_WWDGRSTF /*!< Window watchdog reset flag */ +#if defined(RCC_CSR_BORRSTF) +#define LL_RCC_CSR_BORRSTF RCC_CSR_BORRSTF /*!< BOR reset flag */ +#endif /* RCC_CSR_BORRSTF */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_RCC_ReadReg and LL_RCC_WriteReg functions + * @{ + */ +#define LL_RCC_CIR_LSIRDYIE RCC_CIR_LSIRDYIE /*!< LSI Ready Interrupt Enable */ +#define LL_RCC_CIR_LSERDYIE RCC_CIR_LSERDYIE /*!< LSE Ready Interrupt Enable */ +#define LL_RCC_CIR_HSIRDYIE RCC_CIR_HSIRDYIE /*!< HSI Ready Interrupt Enable */ +#define LL_RCC_CIR_HSERDYIE RCC_CIR_HSERDYIE /*!< HSE Ready Interrupt Enable */ +#define LL_RCC_CIR_PLLRDYIE RCC_CIR_PLLRDYIE /*!< PLL Ready Interrupt Enable */ +#if defined(RCC_PLLI2S_SUPPORT) +#define LL_RCC_CIR_PLLI2SRDYIE RCC_CIR_PLLI2SRDYIE /*!< PLLI2S Ready Interrupt Enable */ +#endif /* RCC_PLLI2S_SUPPORT */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_CIR_PLLSAIRDYIE RCC_CIR_PLLSAIRDYIE /*!< PLLSAI Ready Interrupt Enable */ +#endif /* RCC_PLLSAI_SUPPORT */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_SYS_CLKSOURCE System clock switch + * @{ + */ +#define LL_RCC_SYS_CLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */ +#define LL_RCC_SYS_CLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */ +#define LL_RCC_SYS_CLKSOURCE_PLL RCC_CFGR_SW_PLL /*!< PLL selection as system clock */ +#if defined(RCC_CFGR_SW_PLLR) +#define LL_RCC_SYS_CLKSOURCE_PLLR RCC_CFGR_SW_PLLR /*!< PLLR selection as system clock */ +#endif /* RCC_CFGR_SW_PLLR */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_SYS_CLKSOURCE_STATUS System clock switch status + * @{ + */ +#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ +#define LL_RCC_SYS_CLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ +#define LL_RCC_SYS_CLKSOURCE_STATUS_PLL RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ +#if defined(RCC_PLLR_SYSCLK_SUPPORT) +#define LL_RCC_SYS_CLKSOURCE_STATUS_PLLR RCC_CFGR_SWS_PLLR /*!< PLLR used as system clock */ +#endif /* RCC_PLLR_SYSCLK_SUPPORT */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_SYSCLK_DIV AHB prescaler + * @{ + */ +#define LL_RCC_SYSCLK_DIV_1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */ +#define LL_RCC_SYSCLK_DIV_2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */ +#define LL_RCC_SYSCLK_DIV_4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */ +#define LL_RCC_SYSCLK_DIV_8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */ +#define LL_RCC_SYSCLK_DIV_16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */ +#define LL_RCC_SYSCLK_DIV_64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */ +#define LL_RCC_SYSCLK_DIV_128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */ +#define LL_RCC_SYSCLK_DIV_256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */ +#define LL_RCC_SYSCLK_DIV_512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_APB1_DIV APB low-speed prescaler (APB1) + * @{ + */ +#define LL_RCC_APB1_DIV_1 RCC_CFGR_PPRE1_DIV1 /*!< HCLK not divided */ +#define LL_RCC_APB1_DIV_2 RCC_CFGR_PPRE1_DIV2 /*!< HCLK divided by 2 */ +#define LL_RCC_APB1_DIV_4 RCC_CFGR_PPRE1_DIV4 /*!< HCLK divided by 4 */ +#define LL_RCC_APB1_DIV_8 RCC_CFGR_PPRE1_DIV8 /*!< HCLK divided by 8 */ +#define LL_RCC_APB1_DIV_16 RCC_CFGR_PPRE1_DIV16 /*!< HCLK divided by 16 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_APB2_DIV APB high-speed prescaler (APB2) + * @{ + */ +#define LL_RCC_APB2_DIV_1 RCC_CFGR_PPRE2_DIV1 /*!< HCLK not divided */ +#define LL_RCC_APB2_DIV_2 RCC_CFGR_PPRE2_DIV2 /*!< HCLK divided by 2 */ +#define LL_RCC_APB2_DIV_4 RCC_CFGR_PPRE2_DIV4 /*!< HCLK divided by 4 */ +#define LL_RCC_APB2_DIV_8 RCC_CFGR_PPRE2_DIV8 /*!< HCLK divided by 8 */ +#define LL_RCC_APB2_DIV_16 RCC_CFGR_PPRE2_DIV16 /*!< HCLK divided by 16 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_MCOxSOURCE MCO source selection + * @{ + */ +#define LL_RCC_MCO1SOURCE_HSI (uint32_t)(RCC_CFGR_MCO1|0x00000000U) /*!< HSI selection as MCO1 source */ +#define LL_RCC_MCO1SOURCE_LSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_0 >> 16U)) /*!< LSE selection as MCO1 source */ +#define LL_RCC_MCO1SOURCE_HSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_1 >> 16U)) /*!< HSE selection as MCO1 source */ +#define LL_RCC_MCO1SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO1|((RCC_CFGR_MCO1_1|RCC_CFGR_MCO1_0) >> 16U)) /*!< PLLCLK selection as MCO1 source */ +#if defined(RCC_CFGR_MCO2) +#define LL_RCC_MCO2SOURCE_SYSCLK (uint32_t)(RCC_CFGR_MCO2|0x00000000U) /*!< SYSCLK selection as MCO2 source */ +#define LL_RCC_MCO2SOURCE_PLLI2S (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_0 >> 16U)) /*!< PLLI2S selection as MCO2 source */ +#define LL_RCC_MCO2SOURCE_HSE (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_1 >> 16U)) /*!< HSE selection as MCO2 source */ +#define LL_RCC_MCO2SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO2|((RCC_CFGR_MCO2_1|RCC_CFGR_MCO2_0) >> 16U)) /*!< PLLCLK selection as MCO2 source */ +#endif /* RCC_CFGR_MCO2 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_MCOx_DIV MCO prescaler + * @{ + */ +#define LL_RCC_MCO1_DIV_1 (uint32_t)(RCC_CFGR_MCO1PRE|0x00000000U) /*!< MCO1 not divided */ +#define LL_RCC_MCO1_DIV_2 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE_2 >> 16U)) /*!< MCO1 divided by 2 */ +#define LL_RCC_MCO1_DIV_3 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_0) >> 16U)) /*!< MCO1 divided by 3 */ +#define LL_RCC_MCO1_DIV_4 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_1) >> 16U)) /*!< MCO1 divided by 4 */ +#define LL_RCC_MCO1_DIV_5 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE >> 16U)) /*!< MCO1 divided by 5 */ +#if defined(RCC_CFGR_MCO2PRE) +#define LL_RCC_MCO2_DIV_1 (uint32_t)(RCC_CFGR_MCO2PRE|0x00000000U) /*!< MCO2 not divided */ +#define LL_RCC_MCO2_DIV_2 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE_2 >> 16U)) /*!< MCO2 divided by 2 */ +#define LL_RCC_MCO2_DIV_3 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_0) >> 16U)) /*!< MCO2 divided by 3 */ +#define LL_RCC_MCO2_DIV_4 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_1) >> 16U)) /*!< MCO2 divided by 4 */ +#define LL_RCC_MCO2_DIV_5 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE >> 16U)) /*!< MCO2 divided by 5 */ +#endif /* RCC_CFGR_MCO2PRE */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_RTC_HSEDIV HSE prescaler for RTC clock + * @{ + */ +#define LL_RCC_RTC_NOCLOCK 0x00000000U /*!< HSE not divided */ +#define LL_RCC_RTC_HSE_DIV_2 RCC_CFGR_RTCPRE_1 /*!< HSE clock divided by 2 */ +#define LL_RCC_RTC_HSE_DIV_3 (RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 3 */ +#define LL_RCC_RTC_HSE_DIV_4 RCC_CFGR_RTCPRE_2 /*!< HSE clock divided by 4 */ +#define LL_RCC_RTC_HSE_DIV_5 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 5 */ +#define LL_RCC_RTC_HSE_DIV_6 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 6 */ +#define LL_RCC_RTC_HSE_DIV_7 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 7 */ +#define LL_RCC_RTC_HSE_DIV_8 RCC_CFGR_RTCPRE_3 /*!< HSE clock divided by 8 */ +#define LL_RCC_RTC_HSE_DIV_9 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 9 */ +#define LL_RCC_RTC_HSE_DIV_10 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 10 */ +#define LL_RCC_RTC_HSE_DIV_11 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 11 */ +#define LL_RCC_RTC_HSE_DIV_12 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 12 */ +#define LL_RCC_RTC_HSE_DIV_13 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 13 */ +#define LL_RCC_RTC_HSE_DIV_14 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 14 */ +#define LL_RCC_RTC_HSE_DIV_15 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 15 */ +#define LL_RCC_RTC_HSE_DIV_16 RCC_CFGR_RTCPRE_4 /*!< HSE clock divided by 16 */ +#define LL_RCC_RTC_HSE_DIV_17 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 17 */ +#define LL_RCC_RTC_HSE_DIV_18 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 18 */ +#define LL_RCC_RTC_HSE_DIV_19 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 19 */ +#define LL_RCC_RTC_HSE_DIV_20 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 20 */ +#define LL_RCC_RTC_HSE_DIV_21 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 21 */ +#define LL_RCC_RTC_HSE_DIV_22 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 22 */ +#define LL_RCC_RTC_HSE_DIV_23 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 23 */ +#define LL_RCC_RTC_HSE_DIV_24 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3) /*!< HSE clock divided by 24 */ +#define LL_RCC_RTC_HSE_DIV_25 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 25 */ +#define LL_RCC_RTC_HSE_DIV_26 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 26 */ +#define LL_RCC_RTC_HSE_DIV_27 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 27 */ +#define LL_RCC_RTC_HSE_DIV_28 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 28 */ +#define LL_RCC_RTC_HSE_DIV_29 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 29 */ +#define LL_RCC_RTC_HSE_DIV_30 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 30 */ +#define LL_RCC_RTC_HSE_DIV_31 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 31 */ +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup RCC_LL_EC_PERIPH_FREQUENCY Peripheral clock frequency + * @{ + */ +#define LL_RCC_PERIPH_FREQUENCY_NO 0x00000000U /*!< No clock enabled for the peripheral */ +#define LL_RCC_PERIPH_FREQUENCY_NA 0xFFFFFFFFU /*!< Frequency cannot be provided as external clock */ +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +#if defined(FMPI2C1) +/** @defgroup RCC_LL_EC_FMPI2C1_CLKSOURCE Peripheral FMPI2C clock source selection + * @{ + */ +#define LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as FMPI2C1 clock source */ +#define LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK RCC_DCKCFGR2_FMPI2C1SEL_0 /*!< SYSCLK clock used as FMPI2C1 clock source */ +#define LL_RCC_FMPI2C1_CLKSOURCE_HSI RCC_DCKCFGR2_FMPI2C1SEL_1 /*!< HSI clock used as FMPI2C1 clock source */ +/** + * @} + */ +#endif /* FMPI2C1 */ + +#if defined(LPTIM1) +/** @defgroup RCC_LL_EC_LPTIM1_CLKSOURCE Peripheral LPTIM clock source selection + * @{ + */ +#define LL_RCC_LPTIM1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as LPTIM1 clock */ +#define LL_RCC_LPTIM1_CLKSOURCE_HSI RCC_DCKCFGR2_LPTIM1SEL_0 /*!< LSI oscillator clock used as LPTIM1 clock */ +#define LL_RCC_LPTIM1_CLKSOURCE_LSI RCC_DCKCFGR2_LPTIM1SEL_1 /*!< HSI oscillator clock used as LPTIM1 clock */ +#define LL_RCC_LPTIM1_CLKSOURCE_LSE (uint32_t)(RCC_DCKCFGR2_LPTIM1SEL_1 | RCC_DCKCFGR2_LPTIM1SEL_0) /*!< LSE oscillator clock used as LPTIM1 clock */ +/** + * @} + */ +#endif /* LPTIM1 */ + +#if defined(SAI1) +/** @defgroup RCC_LL_EC_SAIx_CLKSOURCE Peripheral SAI clock source selection + * @{ + */ +#if defined(RCC_DCKCFGR_SAI1SRC) +#define LL_RCC_SAI1_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1SRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 clock source */ +#define LL_RCC_SAI1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 clock source */ +#define LL_RCC_SAI1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_1 >> 16)) /*!< PLL clock used as SAI1 clock source */ +#define LL_RCC_SAI1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC >> 16)) /*!< External pin clock used as SAI1 clock source */ +#endif /* RCC_DCKCFGR_SAI1SRC */ +#if defined(RCC_DCKCFGR_SAI2SRC) +#define LL_RCC_SAI2_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI2SRC | 0x00000000U) /*!< PLLSAI clock used as SAI2 clock source */ +#define LL_RCC_SAI2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_0 >> 16)) /*!< PLLI2S clock used as SAI2 clock source */ +#define LL_RCC_SAI2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_1 >> 16)) /*!< PLL clock used as SAI2 clock source */ +#define LL_RCC_SAI2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC >> 16)) /*!< PLL Main clock used as SAI2 clock source */ +#endif /* RCC_DCKCFGR_SAI2SRC */ +#if defined(RCC_DCKCFGR_SAI1ASRC) +#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) +#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block A clock source */ +#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< External pin used as SAI1 block A clock source */ +#define LL_RCC_SAI1_A_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< PLL clock used as SAI1 block A clock source */ +#define LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC >> 16)) /*!< PLL Main clock used as SAI1 block A clock source */ +#else +#define LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block A clock source */ +#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block A clock source */ +#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< External pin clock used as SAI1 block A clock source */ +#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ +#endif /* RCC_DCKCFGR_SAI1ASRC */ +#if defined(RCC_DCKCFGR_SAI1BSRC) +#if defined(RCC_SAI1B_PLLSOURCE_SUPPORT) +#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block B clock source */ +#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< External pin used as SAI1 block B clock source */ +#define LL_RCC_SAI1_B_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< PLL clock used as SAI1 block B clock source */ +#define LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC >> 16)) /*!< PLL Main clock used as SAI1 block B clock source */ +#else +#define LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block B clock source */ +#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block B clock source */ +#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< External pin clock used as SAI1 block B clock source */ +#endif /* RCC_SAI1B_PLLSOURCE_SUPPORT */ +#endif /* RCC_DCKCFGR_SAI1BSRC */ +/** + * @} + */ +#endif /* SAI1 */ + +#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) +/** @defgroup RCC_LL_EC_SDIOx_CLKSOURCE Peripheral SDIO clock source selection + * @{ + */ +#define LL_RCC_SDIO_CLKSOURCE_PLL48CLK 0x00000000U /*!< PLL 48M domain clock used as SDIO clock */ +#if defined(RCC_DCKCFGR_SDIOSEL) +#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR_SDIOSEL /*!< System clock clock used as SDIO clock */ +#else +#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR2_SDIOSEL /*!< System clock clock used as SDIO clock */ +#endif /* RCC_DCKCFGR_SDIOSEL */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ + +#if defined(DSI) +/** @defgroup RCC_LL_EC_DSI_CLKSOURCE Peripheral DSI clock source selection + * @{ + */ +#define LL_RCC_DSI_CLKSOURCE_PHY 0x00000000U /*!< DSI-PHY clock used as DSI byte lane clock source */ +#define LL_RCC_DSI_CLKSOURCE_PLL RCC_DCKCFGR_DSISEL /*!< PLL clock used as DSI byte lane clock source */ +/** + * @} + */ +#endif /* DSI */ + +#if defined(CEC) +/** @defgroup RCC_LL_EC_CEC_CLKSOURCE Peripheral CEC clock source selection + * @{ + */ +#define LL_RCC_CEC_CLKSOURCE_HSI_DIV488 0x00000000U /*!< HSI oscillator clock divided by 488 used as CEC clock */ +#define LL_RCC_CEC_CLKSOURCE_LSE RCC_DCKCFGR2_CECSEL /*!< LSE oscillator clock used as CEC clock */ +/** + * @} + */ +#endif /* CEC */ + +/** @defgroup RCC_LL_EC_I2S1_CLKSOURCE Peripheral I2S clock source selection + * @{ + */ +#if defined(RCC_CFGR_I2SSRC) +#define LL_RCC_I2S1_CLKSOURCE_PLLI2S 0x00000000U /*!< I2S oscillator clock used as I2S1 clock */ +#define LL_RCC_I2S1_CLKSOURCE_PIN RCC_CFGR_I2SSRC /*!< External pin clock used as I2S1 clock */ +#endif /* RCC_CFGR_I2SSRC */ +#if defined(RCC_DCKCFGR_I2SSRC) +#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2SSRC | 0x00000000U) /*!< PLL clock used as I2S1 clock source */ +#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ +#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_1 >> 16)) /*!< PLL Main clock used as I2S1 clock source */ +#endif /* RCC_DCKCFGR_I2SSRC */ +#if defined(RCC_DCKCFGR_I2S1SRC) +#define LL_RCC_I2S1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S1SRC | 0x00000000U) /*!< PLLI2S clock used as I2S1 clock source */ +#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ +#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_1 >> 16)) /*!< PLL clock used as I2S1 clock source */ +#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC >> 16)) /*!< PLL Main clock used as I2S1 clock source */ +#endif /* RCC_DCKCFGR_I2S1SRC */ +#if defined(RCC_DCKCFGR_I2S2SRC) +#define LL_RCC_I2S2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S2SRC | 0x00000000U) /*!< PLLI2S clock used as I2S2 clock source */ +#define LL_RCC_I2S2_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_0 >> 16)) /*!< External pin used as I2S2 clock source */ +#define LL_RCC_I2S2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_1 >> 16)) /*!< PLL clock used as I2S2 clock source */ +#define LL_RCC_I2S2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC >> 16)) /*!< PLL Main clock used as I2S2 clock source */ +#endif /* RCC_DCKCFGR_I2S2SRC */ +/** + * @} + */ + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +/** @defgroup RCC_LL_EC_CK48M_CLKSOURCE Peripheral 48Mhz domain clock source selection + * @{ + */ +#if defined(RCC_DCKCFGR_CK48MSEL) +#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ +#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ +#endif /* RCC_DCKCFGR_CK48MSEL */ +#if defined(RCC_DCKCFGR2_CK48MSEL) +#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR2_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ +#endif /* RCC_PLLSAI_SUPPORT */ +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +#define LL_RCC_CK48M_CLKSOURCE_PLLI2S RCC_DCKCFGR2_CK48MSEL /*!< PLLI2S oscillator clock used as 48Mhz domain clock */ +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +#endif /* RCC_DCKCFGR2_CK48MSEL */ +/** + * @} + */ + +#if defined(RNG) +/** @defgroup RCC_LL_EC_RNG_CLKSOURCE Peripheral RNG clock source selection + * @{ + */ +#define LL_RCC_RNG_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as RNG clock source */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_RNG_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as RNG clock source */ +#endif /* RCC_PLLSAI_SUPPORT */ +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +#define LL_RCC_RNG_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as RNG clock source */ +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +/** + * @} + */ +#endif /* RNG */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +/** @defgroup RCC_LL_EC_USB_CLKSOURCE Peripheral USB clock source selection + * @{ + */ +#define LL_RCC_USB_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as USB clock source */ +#if defined(RCC_PLLSAI_SUPPORT) +#define LL_RCC_USB_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as USB clock source */ +#endif /* RCC_PLLSAI_SUPPORT */ +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +#define LL_RCC_USB_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as USB clock source */ +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +/** + * @} + */ +#endif /* USB_OTG_FS || USB_OTG_HS */ + +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + +#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) +/** @defgroup RCC_LL_EC_DFSDM1_AUDIO_CLKSOURCE Peripheral DFSDM Audio clock source selection + * @{ + */ +#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM1 Audio clock source */ +#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | (RCC_DCKCFGR_CKDFSDM1ASEL << 16)) /*!< I2S2 clock used as DFSDM1 Audio clock source */ +#if defined(DFSDM2_Channel0) +#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM2 Audio clock source */ +#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | (RCC_DCKCFGR_CKDFSDM2ASEL << 16)) /*!< I2S2 clock used as DFSDM2 Audio clock source */ +#endif /* DFSDM2_Channel0 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_DFSDM1_CLKSOURCE Peripheral DFSDM clock source selection + * @{ + */ +#define LL_RCC_DFSDM1_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM1 clock */ +#define LL_RCC_DFSDM1_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM1 clock */ +#if defined(DFSDM2_Channel0) +#define LL_RCC_DFSDM2_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM2 clock */ +#define LL_RCC_DFSDM2_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM2 clock */ +#endif /* DFSDM2_Channel0 */ +/** + * @} + */ +#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ + +#if defined(FMPI2C1) +/** @defgroup RCC_LL_EC_FMPI2C1 Peripheral FMPI2C get clock source + * @{ + */ +#define LL_RCC_FMPI2C1_CLKSOURCE RCC_DCKCFGR2_FMPI2C1SEL /*!< FMPI2C1 Clock source selection */ +/** + * @} + */ +#endif /* FMPI2C1 */ + +#if defined(SPDIFRX) +/** @defgroup RCC_LL_EC_SPDIFRX_CLKSOURCE Peripheral SPDIFRX clock source selection + * @{ + */ +#define LL_RCC_SPDIFRX1_CLKSOURCE_PLL 0x00000000U /*!< PLL clock used as SPDIFRX clock source */ +#define LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S RCC_DCKCFGR2_SPDIFRXSEL /*!< PLLI2S clock used as SPDIFRX clock source */ +/** + * @} + */ +#endif /* SPDIFRX */ + +#if defined(LPTIM1) +/** @defgroup RCC_LL_EC_LPTIM1 Peripheral LPTIM get clock source + * @{ + */ +#define LL_RCC_LPTIM1_CLKSOURCE RCC_DCKCFGR2_LPTIM1SEL /*!< LPTIM1 Clock source selection */ +/** + * @} + */ +#endif /* LPTIM1 */ + +#if defined(SAI1) +/** @defgroup RCC_LL_EC_SAIx Peripheral SAI get clock source + * @{ + */ +#if defined(RCC_DCKCFGR_SAI1ASRC) +#define LL_RCC_SAI1_A_CLKSOURCE RCC_DCKCFGR_SAI1ASRC /*!< SAI1 block A Clock source selection */ +#endif /* RCC_DCKCFGR_SAI1ASRC */ +#if defined(RCC_DCKCFGR_SAI1BSRC) +#define LL_RCC_SAI1_B_CLKSOURCE RCC_DCKCFGR_SAI1BSRC /*!< SAI1 block B Clock source selection */ +#endif /* RCC_DCKCFGR_SAI1BSRC */ +#if defined(RCC_DCKCFGR_SAI1SRC) +#define LL_RCC_SAI1_CLKSOURCE RCC_DCKCFGR_SAI1SRC /*!< SAI1 Clock source selection */ +#endif /* RCC_DCKCFGR_SAI1SRC */ +#if defined(RCC_DCKCFGR_SAI2SRC) +#define LL_RCC_SAI2_CLKSOURCE RCC_DCKCFGR_SAI2SRC /*!< SAI2 Clock source selection */ +#endif /* RCC_DCKCFGR_SAI2SRC */ +/** + * @} + */ +#endif /* SAI1 */ + +#if defined(SDIO) +/** @defgroup RCC_LL_EC_SDIOx Peripheral SDIO get clock source + * @{ + */ +#if defined(RCC_DCKCFGR_SDIOSEL) +#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR_SDIOSEL /*!< SDIO Clock source selection */ +#elif defined(RCC_DCKCFGR2_SDIOSEL) +#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR2_SDIOSEL /*!< SDIO Clock source selection */ +#else +#define LL_RCC_SDIO_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< SDIO Clock source selection */ +#endif +/** + * @} + */ +#endif /* SDIO */ + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +/** @defgroup RCC_LL_EC_CK48M Peripheral CK48M get clock source + * @{ + */ +#if defined(RCC_DCKCFGR_CK48MSEL) +#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR_CK48MSEL /*!< CK48M Domain clock source selection */ +#endif /* RCC_DCKCFGR_CK48MSEL */ +#if defined(RCC_DCKCFGR2_CK48MSEL) +#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR2_CK48MSEL /*!< CK48M Domain clock source selection */ +#endif /* RCC_DCKCFGR_CK48MSEL */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + +#if defined(RNG) +/** @defgroup RCC_LL_EC_RNG Peripheral RNG get clock source + * @{ + */ +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +#define LL_RCC_RNG_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< RNG Clock source selection */ +#else +#define LL_RCC_RNG_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< RNG Clock source selection */ +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ +/** + * @} + */ +#endif /* RNG */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +/** @defgroup RCC_LL_EC_USB Peripheral USB get clock source + * @{ + */ +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +#define LL_RCC_USB_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< USB Clock source selection */ +#else +#define LL_RCC_USB_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< USB Clock source selection */ +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ +/** + * @} + */ +#endif /* USB_OTG_FS || USB_OTG_HS */ + +#if defined(CEC) +/** @defgroup RCC_LL_EC_CEC Peripheral CEC get clock source + * @{ + */ +#define LL_RCC_CEC_CLKSOURCE RCC_DCKCFGR2_CECSEL /*!< CEC Clock source selection */ +/** + * @} + */ +#endif /* CEC */ + +/** @defgroup RCC_LL_EC_I2S1 Peripheral I2S get clock source + * @{ + */ +#if defined(RCC_CFGR_I2SSRC) +#define LL_RCC_I2S1_CLKSOURCE RCC_CFGR_I2SSRC /*!< I2S1 Clock source selection */ +#endif /* RCC_CFGR_I2SSRC */ +#if defined(RCC_DCKCFGR_I2SSRC) +#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2SSRC /*!< I2S1 Clock source selection */ +#endif /* RCC_DCKCFGR_I2SSRC */ +#if defined(RCC_DCKCFGR_I2S1SRC) +#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2S1SRC /*!< I2S1 Clock source selection */ +#endif /* RCC_DCKCFGR_I2S1SRC */ +#if defined(RCC_DCKCFGR_I2S2SRC) +#define LL_RCC_I2S2_CLKSOURCE RCC_DCKCFGR_I2S2SRC /*!< I2S2 Clock source selection */ +#endif /* RCC_DCKCFGR_I2S2SRC */ +/** + * @} + */ + +#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) +/** @defgroup RCC_LL_EC_DFSDM_AUDIO Peripheral DFSDM Audio get clock source + * @{ + */ +#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM1ASEL /*!< DFSDM1 Audio Clock source selection */ +#if defined(DFSDM2_Channel0) +#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM2ASEL /*!< DFSDM2 Audio Clock source selection */ +#endif /* DFSDM2_Channel0 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_DFSDM Peripheral DFSDM get clock source + * @{ + */ +#define LL_RCC_DFSDM1_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM1 Clock source selection */ +#if defined(DFSDM2_Channel0) +#define LL_RCC_DFSDM2_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM2 Clock source selection */ +#endif /* DFSDM2_Channel0 */ +/** + * @} + */ +#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ + +#if defined(SPDIFRX) +/** @defgroup RCC_LL_EC_SPDIFRX Peripheral SPDIFRX get clock source + * @{ + */ +#define LL_RCC_SPDIFRX1_CLKSOURCE RCC_DCKCFGR2_SPDIFRXSEL /*!< SPDIFRX Clock source selection */ +/** + * @} + */ +#endif /* SPDIFRX */ + +#if defined(DSI) +/** @defgroup RCC_LL_EC_DSI Peripheral DSI get clock source + * @{ + */ +#define LL_RCC_DSI_CLKSOURCE RCC_DCKCFGR_DSISEL /*!< DSI Clock source selection */ +/** + * @} + */ +#endif /* DSI */ + +#if defined(LTDC) +/** @defgroup RCC_LL_EC_LTDC Peripheral LTDC get clock source + * @{ + */ +#define LL_RCC_LTDC_CLKSOURCE RCC_DCKCFGR_PLLSAIDIVR /*!< LTDC Clock source selection */ +/** + * @} + */ +#endif /* LTDC */ + + +/** @defgroup RCC_LL_EC_RTC_CLKSOURCE RTC clock source selection + * @{ + */ +#define LL_RCC_RTC_CLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */ +#define LL_RCC_RTC_CLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */ +#define LL_RCC_RTC_CLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */ +#define LL_RCC_RTC_CLKSOURCE_HSE RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by HSE prescaler used as RTC clock */ +/** + * @} + */ + +#if defined(RCC_DCKCFGR_TIMPRE) +/** @defgroup RCC_LL_EC_TIM_CLKPRESCALER Timers clocks prescalers selection + * @{ + */ +#define LL_RCC_TIM_PRESCALER_TWICE 0x00000000U /*!< Timers clock to twice PCLK */ +#define LL_RCC_TIM_PRESCALER_FOUR_TIMES RCC_DCKCFGR_TIMPRE /*!< Timers clock to four time PCLK */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_TIMPRE */ + +/** @defgroup RCC_LL_EC_PLLSOURCE PLL, PLLI2S and PLLSAI entry clock source + * @{ + */ +#define LL_RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI /*!< HSI16 clock selected as PLL entry clock source */ +#define LL_RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE /*!< HSE clock selected as PLL entry clock source */ +#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) +#define LL_RCC_PLLI2SSOURCE_PIN (RCC_PLLI2SCFGR_PLLI2SSRC | 0x80U) /*!< I2S External pin input clock selected as PLLI2S entry clock source */ +#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_PLLM_DIV PLL, PLLI2S and PLLSAI division factor + * @{ + */ +#define LL_RCC_PLLM_DIV_2 (RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 2 */ +#define LL_RCC_PLLM_DIV_3 (RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 3 */ +#define LL_RCC_PLLM_DIV_4 (RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 4 */ +#define LL_RCC_PLLM_DIV_5 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 5 */ +#define LL_RCC_PLLM_DIV_6 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 6 */ +#define LL_RCC_PLLM_DIV_7 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 7 */ +#define LL_RCC_PLLM_DIV_8 (RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 8 */ +#define LL_RCC_PLLM_DIV_9 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 9 */ +#define LL_RCC_PLLM_DIV_10 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 10 */ +#define LL_RCC_PLLM_DIV_11 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 11 */ +#define LL_RCC_PLLM_DIV_12 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 12 */ +#define LL_RCC_PLLM_DIV_13 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 13 */ +#define LL_RCC_PLLM_DIV_14 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 14 */ +#define LL_RCC_PLLM_DIV_15 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 15 */ +#define LL_RCC_PLLM_DIV_16 (RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 16 */ +#define LL_RCC_PLLM_DIV_17 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 17 */ +#define LL_RCC_PLLM_DIV_18 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 18 */ +#define LL_RCC_PLLM_DIV_19 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 19 */ +#define LL_RCC_PLLM_DIV_20 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 20 */ +#define LL_RCC_PLLM_DIV_21 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 21 */ +#define LL_RCC_PLLM_DIV_22 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 22 */ +#define LL_RCC_PLLM_DIV_23 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 23 */ +#define LL_RCC_PLLM_DIV_24 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 24 */ +#define LL_RCC_PLLM_DIV_25 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 25 */ +#define LL_RCC_PLLM_DIV_26 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 26 */ +#define LL_RCC_PLLM_DIV_27 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 27 */ +#define LL_RCC_PLLM_DIV_28 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 28 */ +#define LL_RCC_PLLM_DIV_29 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 29 */ +#define LL_RCC_PLLM_DIV_30 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 30 */ +#define LL_RCC_PLLM_DIV_31 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 31 */ +#define LL_RCC_PLLM_DIV_32 (RCC_PLLCFGR_PLLM_5) /*!< PLL, PLLI2S and PLLSAI division factor by 32 */ +#define LL_RCC_PLLM_DIV_33 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 33 */ +#define LL_RCC_PLLM_DIV_34 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 34 */ +#define LL_RCC_PLLM_DIV_35 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 35 */ +#define LL_RCC_PLLM_DIV_36 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 36 */ +#define LL_RCC_PLLM_DIV_37 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 37 */ +#define LL_RCC_PLLM_DIV_38 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 38 */ +#define LL_RCC_PLLM_DIV_39 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 39 */ +#define LL_RCC_PLLM_DIV_40 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 40 */ +#define LL_RCC_PLLM_DIV_41 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 41 */ +#define LL_RCC_PLLM_DIV_42 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 42 */ +#define LL_RCC_PLLM_DIV_43 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 43 */ +#define LL_RCC_PLLM_DIV_44 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 44 */ +#define LL_RCC_PLLM_DIV_45 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 45 */ +#define LL_RCC_PLLM_DIV_46 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 46 */ +#define LL_RCC_PLLM_DIV_47 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 47 */ +#define LL_RCC_PLLM_DIV_48 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 48 */ +#define LL_RCC_PLLM_DIV_49 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 49 */ +#define LL_RCC_PLLM_DIV_50 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 50 */ +#define LL_RCC_PLLM_DIV_51 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 51 */ +#define LL_RCC_PLLM_DIV_52 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 52 */ +#define LL_RCC_PLLM_DIV_53 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 53 */ +#define LL_RCC_PLLM_DIV_54 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 54 */ +#define LL_RCC_PLLM_DIV_55 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 55 */ +#define LL_RCC_PLLM_DIV_56 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 56 */ +#define LL_RCC_PLLM_DIV_57 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 57 */ +#define LL_RCC_PLLM_DIV_58 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 58 */ +#define LL_RCC_PLLM_DIV_59 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 59 */ +#define LL_RCC_PLLM_DIV_60 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 60 */ +#define LL_RCC_PLLM_DIV_61 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 61 */ +#define LL_RCC_PLLM_DIV_62 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 62 */ +#define LL_RCC_PLLM_DIV_63 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 63 */ +/** + * @} + */ + +#if defined(RCC_PLLCFGR_PLLR) +/** @defgroup RCC_LL_EC_PLLR_DIV PLL division factor (PLLR) + * @{ + */ +#define LL_RCC_PLLR_DIV_2 (RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 2 */ +#define LL_RCC_PLLR_DIV_3 (RCC_PLLCFGR_PLLR_1|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 3 */ +#define LL_RCC_PLLR_DIV_4 (RCC_PLLCFGR_PLLR_2) /*!< Main PLL division factor for PLLCLK (system clock) by 4 */ +#define LL_RCC_PLLR_DIV_5 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 5 */ +#define LL_RCC_PLLR_DIV_6 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 6 */ +#define LL_RCC_PLLR_DIV_7 (RCC_PLLCFGR_PLLR) /*!< Main PLL division factor for PLLCLK (system clock) by 7 */ +/** + * @} + */ +#endif /* RCC_PLLCFGR_PLLR */ + +#if defined(RCC_DCKCFGR_PLLDIVR) +/** @defgroup RCC_LL_EC_PLLDIVR PLLDIVR division factor (PLLDIVR) + * @{ + */ +#define LL_RCC_PLLDIVR_DIV_1 (RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 1 */ +#define LL_RCC_PLLDIVR_DIV_2 (RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 2 */ +#define LL_RCC_PLLDIVR_DIV_3 (RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 3 */ +#define LL_RCC_PLLDIVR_DIV_4 (RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 4 */ +#define LL_RCC_PLLDIVR_DIV_5 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 5 */ +#define LL_RCC_PLLDIVR_DIV_6 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 6 */ +#define LL_RCC_PLLDIVR_DIV_7 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 7 */ +#define LL_RCC_PLLDIVR_DIV_8 (RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 8 */ +#define LL_RCC_PLLDIVR_DIV_9 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 9 */ +#define LL_RCC_PLLDIVR_DIV_10 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 10 */ +#define LL_RCC_PLLDIVR_DIV_11 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 11 */ +#define LL_RCC_PLLDIVR_DIV_12 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 12 */ +#define LL_RCC_PLLDIVR_DIV_13 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 13 */ +#define LL_RCC_PLLDIVR_DIV_14 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 14 */ +#define LL_RCC_PLLDIVR_DIV_15 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 15 */ +#define LL_RCC_PLLDIVR_DIV_16 (RCC_DCKCFGR_PLLDIVR_4) /*!< PLL division factor for PLLDIVR output by 16 */ +#define LL_RCC_PLLDIVR_DIV_17 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 17 */ +#define LL_RCC_PLLDIVR_DIV_18 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 18 */ +#define LL_RCC_PLLDIVR_DIV_19 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 19 */ +#define LL_RCC_PLLDIVR_DIV_20 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 20 */ +#define LL_RCC_PLLDIVR_DIV_21 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 21 */ +#define LL_RCC_PLLDIVR_DIV_22 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 22 */ +#define LL_RCC_PLLDIVR_DIV_23 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 23 */ +#define LL_RCC_PLLDIVR_DIV_24 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 24 */ +#define LL_RCC_PLLDIVR_DIV_25 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 25 */ +#define LL_RCC_PLLDIVR_DIV_26 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 26 */ +#define LL_RCC_PLLDIVR_DIV_27 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 27 */ +#define LL_RCC_PLLDIVR_DIV_28 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 28 */ +#define LL_RCC_PLLDIVR_DIV_29 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 29 */ +#define LL_RCC_PLLDIVR_DIV_30 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 30 */ +#define LL_RCC_PLLDIVR_DIV_31 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 31 */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_PLLDIVR */ + +/** @defgroup RCC_LL_EC_PLLP_DIV PLL division factor (PLLP) + * @{ + */ +#define LL_RCC_PLLP_DIV_2 0x00000000U /*!< Main PLL division factor for PLLP output by 2 */ +#define LL_RCC_PLLP_DIV_4 RCC_PLLCFGR_PLLP_0 /*!< Main PLL division factor for PLLP output by 4 */ +#define LL_RCC_PLLP_DIV_6 RCC_PLLCFGR_PLLP_1 /*!< Main PLL division factor for PLLP output by 6 */ +#define LL_RCC_PLLP_DIV_8 (RCC_PLLCFGR_PLLP_1 | RCC_PLLCFGR_PLLP_0) /*!< Main PLL division factor for PLLP output by 8 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_PLLQ_DIV PLL division factor (PLLQ) + * @{ + */ +#define LL_RCC_PLLQ_DIV_2 RCC_PLLCFGR_PLLQ_1 /*!< Main PLL division factor for PLLQ output by 2 */ +#define LL_RCC_PLLQ_DIV_3 (RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 3 */ +#define LL_RCC_PLLQ_DIV_4 RCC_PLLCFGR_PLLQ_2 /*!< Main PLL division factor for PLLQ output by 4 */ +#define LL_RCC_PLLQ_DIV_5 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 5 */ +#define LL_RCC_PLLQ_DIV_6 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 6 */ +#define LL_RCC_PLLQ_DIV_7 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 7 */ +#define LL_RCC_PLLQ_DIV_8 RCC_PLLCFGR_PLLQ_3 /*!< Main PLL division factor for PLLQ output by 8 */ +#define LL_RCC_PLLQ_DIV_9 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 9 */ +#define LL_RCC_PLLQ_DIV_10 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 10 */ +#define LL_RCC_PLLQ_DIV_11 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 11 */ +#define LL_RCC_PLLQ_DIV_12 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2) /*!< Main PLL division factor for PLLQ output by 12 */ +#define LL_RCC_PLLQ_DIV_13 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 13 */ +#define LL_RCC_PLLQ_DIV_14 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 14 */ +#define LL_RCC_PLLQ_DIV_15 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 15 */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_PLL_SPRE_SEL PLL Spread Spectrum Selection + * @{ + */ +#define LL_RCC_SPREAD_SELECT_CENTER 0x00000000U /*!< PLL center spread spectrum selection */ +#define LL_RCC_SPREAD_SELECT_DOWN RCC_SSCGR_SPREADSEL /*!< PLL down spread spectrum selection */ +/** + * @} + */ + +#if defined(RCC_PLLI2S_SUPPORT) +/** @defgroup RCC_LL_EC_PLLI2SM PLLI2SM division factor (PLLI2SM) + * @{ + */ +#if defined(RCC_PLLI2SCFGR_PLLI2SM) +#define LL_RCC_PLLI2SM_DIV_2 (RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 2 */ +#define LL_RCC_PLLI2SM_DIV_3 (RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 3 */ +#define LL_RCC_PLLI2SM_DIV_4 (RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 4 */ +#define LL_RCC_PLLI2SM_DIV_5 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 5 */ +#define LL_RCC_PLLI2SM_DIV_6 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 6 */ +#define LL_RCC_PLLI2SM_DIV_7 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 7 */ +#define LL_RCC_PLLI2SM_DIV_8 (RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 8 */ +#define LL_RCC_PLLI2SM_DIV_9 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 9 */ +#define LL_RCC_PLLI2SM_DIV_10 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 10 */ +#define LL_RCC_PLLI2SM_DIV_11 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 11 */ +#define LL_RCC_PLLI2SM_DIV_12 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 12 */ +#define LL_RCC_PLLI2SM_DIV_13 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 13 */ +#define LL_RCC_PLLI2SM_DIV_14 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 14 */ +#define LL_RCC_PLLI2SM_DIV_15 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 15 */ +#define LL_RCC_PLLI2SM_DIV_16 (RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 16 */ +#define LL_RCC_PLLI2SM_DIV_17 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 17 */ +#define LL_RCC_PLLI2SM_DIV_18 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 18 */ +#define LL_RCC_PLLI2SM_DIV_19 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 19 */ +#define LL_RCC_PLLI2SM_DIV_20 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 20 */ +#define LL_RCC_PLLI2SM_DIV_21 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 21 */ +#define LL_RCC_PLLI2SM_DIV_22 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 22 */ +#define LL_RCC_PLLI2SM_DIV_23 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 23 */ +#define LL_RCC_PLLI2SM_DIV_24 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 24 */ +#define LL_RCC_PLLI2SM_DIV_25 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 25 */ +#define LL_RCC_PLLI2SM_DIV_26 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 26 */ +#define LL_RCC_PLLI2SM_DIV_27 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 27 */ +#define LL_RCC_PLLI2SM_DIV_28 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 28 */ +#define LL_RCC_PLLI2SM_DIV_29 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 29 */ +#define LL_RCC_PLLI2SM_DIV_30 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 30 */ +#define LL_RCC_PLLI2SM_DIV_31 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 31 */ +#define LL_RCC_PLLI2SM_DIV_32 (RCC_PLLI2SCFGR_PLLI2SM_5) /*!< PLLI2S division factor for PLLI2SM output by 32 */ +#define LL_RCC_PLLI2SM_DIV_33 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 33 */ +#define LL_RCC_PLLI2SM_DIV_34 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 34 */ +#define LL_RCC_PLLI2SM_DIV_35 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 35 */ +#define LL_RCC_PLLI2SM_DIV_36 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 36 */ +#define LL_RCC_PLLI2SM_DIV_37 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 37 */ +#define LL_RCC_PLLI2SM_DIV_38 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 38 */ +#define LL_RCC_PLLI2SM_DIV_39 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 39 */ +#define LL_RCC_PLLI2SM_DIV_40 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 40 */ +#define LL_RCC_PLLI2SM_DIV_41 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 41 */ +#define LL_RCC_PLLI2SM_DIV_42 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 42 */ +#define LL_RCC_PLLI2SM_DIV_43 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 43 */ +#define LL_RCC_PLLI2SM_DIV_44 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 44 */ +#define LL_RCC_PLLI2SM_DIV_45 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 45 */ +#define LL_RCC_PLLI2SM_DIV_46 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 46 */ +#define LL_RCC_PLLI2SM_DIV_47 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 47 */ +#define LL_RCC_PLLI2SM_DIV_48 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 48 */ +#define LL_RCC_PLLI2SM_DIV_49 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 49 */ +#define LL_RCC_PLLI2SM_DIV_50 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 50 */ +#define LL_RCC_PLLI2SM_DIV_51 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 51 */ +#define LL_RCC_PLLI2SM_DIV_52 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 52 */ +#define LL_RCC_PLLI2SM_DIV_53 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 53 */ +#define LL_RCC_PLLI2SM_DIV_54 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 54 */ +#define LL_RCC_PLLI2SM_DIV_55 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 55 */ +#define LL_RCC_PLLI2SM_DIV_56 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 56 */ +#define LL_RCC_PLLI2SM_DIV_57 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 57 */ +#define LL_RCC_PLLI2SM_DIV_58 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 58 */ +#define LL_RCC_PLLI2SM_DIV_59 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 59 */ +#define LL_RCC_PLLI2SM_DIV_60 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 60 */ +#define LL_RCC_PLLI2SM_DIV_61 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 61 */ +#define LL_RCC_PLLI2SM_DIV_62 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 62 */ +#define LL_RCC_PLLI2SM_DIV_63 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 63 */ +#else +#define LL_RCC_PLLI2SM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLI2S division factor for PLLI2SM output by 2 */ +#define LL_RCC_PLLI2SM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLI2S division factor for PLLI2SM output by 3 */ +#define LL_RCC_PLLI2SM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLI2S division factor for PLLI2SM output by 4 */ +#define LL_RCC_PLLI2SM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLI2S division factor for PLLI2SM output by 5 */ +#define LL_RCC_PLLI2SM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLI2S division factor for PLLI2SM output by 6 */ +#define LL_RCC_PLLI2SM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLI2S division factor for PLLI2SM output by 7 */ +#define LL_RCC_PLLI2SM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLI2S division factor for PLLI2SM output by 8 */ +#define LL_RCC_PLLI2SM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLI2S division factor for PLLI2SM output by 9 */ +#define LL_RCC_PLLI2SM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLI2S division factor for PLLI2SM output by 10 */ +#define LL_RCC_PLLI2SM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLI2S division factor for PLLI2SM output by 11 */ +#define LL_RCC_PLLI2SM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLI2S division factor for PLLI2SM output by 12 */ +#define LL_RCC_PLLI2SM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLI2S division factor for PLLI2SM output by 13 */ +#define LL_RCC_PLLI2SM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLI2S division factor for PLLI2SM output by 14 */ +#define LL_RCC_PLLI2SM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLI2S division factor for PLLI2SM output by 15 */ +#define LL_RCC_PLLI2SM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLI2S division factor for PLLI2SM output by 16 */ +#define LL_RCC_PLLI2SM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLI2S division factor for PLLI2SM output by 17 */ +#define LL_RCC_PLLI2SM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLI2S division factor for PLLI2SM output by 18 */ +#define LL_RCC_PLLI2SM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLI2S division factor for PLLI2SM output by 19 */ +#define LL_RCC_PLLI2SM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLI2S division factor for PLLI2SM output by 20 */ +#define LL_RCC_PLLI2SM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLI2S division factor for PLLI2SM output by 21 */ +#define LL_RCC_PLLI2SM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLI2S division factor for PLLI2SM output by 22 */ +#define LL_RCC_PLLI2SM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLI2S division factor for PLLI2SM output by 23 */ +#define LL_RCC_PLLI2SM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLI2S division factor for PLLI2SM output by 24 */ +#define LL_RCC_PLLI2SM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLI2S division factor for PLLI2SM output by 25 */ +#define LL_RCC_PLLI2SM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLI2S division factor for PLLI2SM output by 26 */ +#define LL_RCC_PLLI2SM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLI2S division factor for PLLI2SM output by 27 */ +#define LL_RCC_PLLI2SM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLI2S division factor for PLLI2SM output by 28 */ +#define LL_RCC_PLLI2SM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLI2S division factor for PLLI2SM output by 29 */ +#define LL_RCC_PLLI2SM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLI2S division factor for PLLI2SM output by 30 */ +#define LL_RCC_PLLI2SM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLI2S division factor for PLLI2SM output by 31 */ +#define LL_RCC_PLLI2SM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLI2S division factor for PLLI2SM output by 32 */ +#define LL_RCC_PLLI2SM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLI2S division factor for PLLI2SM output by 33 */ +#define LL_RCC_PLLI2SM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLI2S division factor for PLLI2SM output by 34 */ +#define LL_RCC_PLLI2SM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLI2S division factor for PLLI2SM output by 35 */ +#define LL_RCC_PLLI2SM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLI2S division factor for PLLI2SM output by 36 */ +#define LL_RCC_PLLI2SM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLI2S division factor for PLLI2SM output by 37 */ +#define LL_RCC_PLLI2SM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLI2S division factor for PLLI2SM output by 38 */ +#define LL_RCC_PLLI2SM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLI2S division factor for PLLI2SM output by 39 */ +#define LL_RCC_PLLI2SM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLI2S division factor for PLLI2SM output by 40 */ +#define LL_RCC_PLLI2SM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLI2S division factor for PLLI2SM output by 41 */ +#define LL_RCC_PLLI2SM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLI2S division factor for PLLI2SM output by 42 */ +#define LL_RCC_PLLI2SM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLI2S division factor for PLLI2SM output by 43 */ +#define LL_RCC_PLLI2SM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLI2S division factor for PLLI2SM output by 44 */ +#define LL_RCC_PLLI2SM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLI2S division factor for PLLI2SM output by 45 */ +#define LL_RCC_PLLI2SM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLI2S division factor for PLLI2SM output by 46 */ +#define LL_RCC_PLLI2SM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLI2S division factor for PLLI2SM output by 47 */ +#define LL_RCC_PLLI2SM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLI2S division factor for PLLI2SM output by 48 */ +#define LL_RCC_PLLI2SM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLI2S division factor for PLLI2SM output by 49 */ +#define LL_RCC_PLLI2SM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLI2S division factor for PLLI2SM output by 50 */ +#define LL_RCC_PLLI2SM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLI2S division factor for PLLI2SM output by 51 */ +#define LL_RCC_PLLI2SM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLI2S division factor for PLLI2SM output by 52 */ +#define LL_RCC_PLLI2SM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLI2S division factor for PLLI2SM output by 53 */ +#define LL_RCC_PLLI2SM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLI2S division factor for PLLI2SM output by 54 */ +#define LL_RCC_PLLI2SM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLI2S division factor for PLLI2SM output by 55 */ +#define LL_RCC_PLLI2SM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLI2S division factor for PLLI2SM output by 56 */ +#define LL_RCC_PLLI2SM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLI2S division factor for PLLI2SM output by 57 */ +#define LL_RCC_PLLI2SM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLI2S division factor for PLLI2SM output by 58 */ +#define LL_RCC_PLLI2SM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLI2S division factor for PLLI2SM output by 59 */ +#define LL_RCC_PLLI2SM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLI2S division factor for PLLI2SM output by 60 */ +#define LL_RCC_PLLI2SM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLI2S division factor for PLLI2SM output by 61 */ +#define LL_RCC_PLLI2SM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLI2S division factor for PLLI2SM output by 62 */ +#define LL_RCC_PLLI2SM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLI2S division factor for PLLI2SM output by 63 */ +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ +/** + * @} + */ + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) +/** @defgroup RCC_LL_EC_PLLI2SQ PLLI2SQ division factor (PLLI2SQ) + * @{ + */ +#define LL_RCC_PLLI2SQ_DIV_2 RCC_PLLI2SCFGR_PLLI2SQ_1 /*!< PLLI2S division factor for PLLI2SQ output by 2 */ +#define LL_RCC_PLLI2SQ_DIV_3 (RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 3 */ +#define LL_RCC_PLLI2SQ_DIV_4 RCC_PLLI2SCFGR_PLLI2SQ_2 /*!< PLLI2S division factor for PLLI2SQ output by 4 */ +#define LL_RCC_PLLI2SQ_DIV_5 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 5 */ +#define LL_RCC_PLLI2SQ_DIV_6 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 6 */ +#define LL_RCC_PLLI2SQ_DIV_7 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 7 */ +#define LL_RCC_PLLI2SQ_DIV_8 RCC_PLLI2SCFGR_PLLI2SQ_3 /*!< PLLI2S division factor for PLLI2SQ output by 8 */ +#define LL_RCC_PLLI2SQ_DIV_9 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 9 */ +#define LL_RCC_PLLI2SQ_DIV_10 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 10 */ +#define LL_RCC_PLLI2SQ_DIV_11 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 11 */ +#define LL_RCC_PLLI2SQ_DIV_12 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2) /*!< PLLI2S division factor for PLLI2SQ output by 12 */ +#define LL_RCC_PLLI2SQ_DIV_13 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 13 */ +#define LL_RCC_PLLI2SQ_DIV_14 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 14 */ +#define LL_RCC_PLLI2SQ_DIV_15 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 15 */ +/** + * @} + */ +#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ + +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) +/** @defgroup RCC_LL_EC_PLLI2SDIVQ PLLI2SDIVQ division factor (PLLI2SDIVQ) + * @{ + */ +#define LL_RCC_PLLI2SDIVQ_DIV_1 0x00000000U /*!< PLLI2S division factor for PLLI2SDIVQ output by 1 */ +#define LL_RCC_PLLI2SDIVQ_DIV_2 RCC_DCKCFGR_PLLI2SDIVQ_0 /*!< PLLI2S division factor for PLLI2SDIVQ output by 2 */ +#define LL_RCC_PLLI2SDIVQ_DIV_3 RCC_DCKCFGR_PLLI2SDIVQ_1 /*!< PLLI2S division factor for PLLI2SDIVQ output by 3 */ +#define LL_RCC_PLLI2SDIVQ_DIV_4 (RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 4 */ +#define LL_RCC_PLLI2SDIVQ_DIV_5 RCC_DCKCFGR_PLLI2SDIVQ_2 /*!< PLLI2S division factor for PLLI2SDIVQ output by 5 */ +#define LL_RCC_PLLI2SDIVQ_DIV_6 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 6 */ +#define LL_RCC_PLLI2SDIVQ_DIV_7 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 7 */ +#define LL_RCC_PLLI2SDIVQ_DIV_8 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 8 */ +#define LL_RCC_PLLI2SDIVQ_DIV_9 RCC_DCKCFGR_PLLI2SDIVQ_3 /*!< PLLI2S division factor for PLLI2SDIVQ output by 9 */ +#define LL_RCC_PLLI2SDIVQ_DIV_10 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 10 */ +#define LL_RCC_PLLI2SDIVQ_DIV_11 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 11 */ +#define LL_RCC_PLLI2SDIVQ_DIV_12 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 12 */ +#define LL_RCC_PLLI2SDIVQ_DIV_13 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 13 */ +#define LL_RCC_PLLI2SDIVQ_DIV_14 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 14 */ +#define LL_RCC_PLLI2SDIVQ_DIV_15 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 15 */ +#define LL_RCC_PLLI2SDIVQ_DIV_16 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 16 */ +#define LL_RCC_PLLI2SDIVQ_DIV_17 RCC_DCKCFGR_PLLI2SDIVQ_4 /*!< PLLI2S division factor for PLLI2SDIVQ output by 17 */ +#define LL_RCC_PLLI2SDIVQ_DIV_18 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 18 */ +#define LL_RCC_PLLI2SDIVQ_DIV_19 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 19 */ +#define LL_RCC_PLLI2SDIVQ_DIV_20 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 20 */ +#define LL_RCC_PLLI2SDIVQ_DIV_21 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 21 */ +#define LL_RCC_PLLI2SDIVQ_DIV_22 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 22 */ +#define LL_RCC_PLLI2SDIVQ_DIV_23 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 23 */ +#define LL_RCC_PLLI2SDIVQ_DIV_24 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 24 */ +#define LL_RCC_PLLI2SDIVQ_DIV_25 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3) /*!< PLLI2S division factor for PLLI2SDIVQ output by 25 */ +#define LL_RCC_PLLI2SDIVQ_DIV_26 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 26 */ +#define LL_RCC_PLLI2SDIVQ_DIV_27 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 27 */ +#define LL_RCC_PLLI2SDIVQ_DIV_28 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 28 */ +#define LL_RCC_PLLI2SDIVQ_DIV_29 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 29 */ +#define LL_RCC_PLLI2SDIVQ_DIV_30 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 30 */ +#define LL_RCC_PLLI2SDIVQ_DIV_31 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 31 */ +#define LL_RCC_PLLI2SDIVQ_DIV_32 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 32 */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ + +#if defined(RCC_DCKCFGR_PLLI2SDIVR) +/** @defgroup RCC_LL_EC_PLLI2SDIVR PLLI2SDIVR division factor (PLLI2SDIVR) + * @{ + */ +#define LL_RCC_PLLI2SDIVR_DIV_1 (RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 1 */ +#define LL_RCC_PLLI2SDIVR_DIV_2 (RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 2 */ +#define LL_RCC_PLLI2SDIVR_DIV_3 (RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 3 */ +#define LL_RCC_PLLI2SDIVR_DIV_4 (RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 4 */ +#define LL_RCC_PLLI2SDIVR_DIV_5 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 5 */ +#define LL_RCC_PLLI2SDIVR_DIV_6 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 6 */ +#define LL_RCC_PLLI2SDIVR_DIV_7 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 7 */ +#define LL_RCC_PLLI2SDIVR_DIV_8 (RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 8 */ +#define LL_RCC_PLLI2SDIVR_DIV_9 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 9 */ +#define LL_RCC_PLLI2SDIVR_DIV_10 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 10 */ +#define LL_RCC_PLLI2SDIVR_DIV_11 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 11 */ +#define LL_RCC_PLLI2SDIVR_DIV_12 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 12 */ +#define LL_RCC_PLLI2SDIVR_DIV_13 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 13 */ +#define LL_RCC_PLLI2SDIVR_DIV_14 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 14 */ +#define LL_RCC_PLLI2SDIVR_DIV_15 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 15 */ +#define LL_RCC_PLLI2SDIVR_DIV_16 (RCC_DCKCFGR_PLLI2SDIVR_4) /*!< PLLI2S division factor for PLLI2SDIVR output by 16 */ +#define LL_RCC_PLLI2SDIVR_DIV_17 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 17 */ +#define LL_RCC_PLLI2SDIVR_DIV_18 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 18 */ +#define LL_RCC_PLLI2SDIVR_DIV_19 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 19 */ +#define LL_RCC_PLLI2SDIVR_DIV_20 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 20 */ +#define LL_RCC_PLLI2SDIVR_DIV_21 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 21 */ +#define LL_RCC_PLLI2SDIVR_DIV_22 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 22 */ +#define LL_RCC_PLLI2SDIVR_DIV_23 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 23 */ +#define LL_RCC_PLLI2SDIVR_DIV_24 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 24 */ +#define LL_RCC_PLLI2SDIVR_DIV_25 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 25 */ +#define LL_RCC_PLLI2SDIVR_DIV_26 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 26 */ +#define LL_RCC_PLLI2SDIVR_DIV_27 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 27 */ +#define LL_RCC_PLLI2SDIVR_DIV_28 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 28 */ +#define LL_RCC_PLLI2SDIVR_DIV_29 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 29 */ +#define LL_RCC_PLLI2SDIVR_DIV_30 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 30 */ +#define LL_RCC_PLLI2SDIVR_DIV_31 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 31 */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_PLLI2SDIVR */ + +/** @defgroup RCC_LL_EC_PLLI2SR PLLI2SR division factor (PLLI2SR) + * @{ + */ +#define LL_RCC_PLLI2SR_DIV_2 RCC_PLLI2SCFGR_PLLI2SR_1 /*!< PLLI2S division factor for PLLI2SR output by 2 */ +#define LL_RCC_PLLI2SR_DIV_3 (RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 3 */ +#define LL_RCC_PLLI2SR_DIV_4 RCC_PLLI2SCFGR_PLLI2SR_2 /*!< PLLI2S division factor for PLLI2SR output by 4 */ +#define LL_RCC_PLLI2SR_DIV_5 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 5 */ +#define LL_RCC_PLLI2SR_DIV_6 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1) /*!< PLLI2S division factor for PLLI2SR output by 6 */ +#define LL_RCC_PLLI2SR_DIV_7 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 7 */ +/** + * @} + */ + +#if defined(RCC_PLLI2SCFGR_PLLI2SP) +/** @defgroup RCC_LL_EC_PLLI2SP PLLI2SP division factor (PLLI2SP) + * @{ + */ +#define LL_RCC_PLLI2SP_DIV_2 0x00000000U /*!< PLLI2S division factor for PLLI2SP output by 2 */ +#define LL_RCC_PLLI2SP_DIV_4 RCC_PLLI2SCFGR_PLLI2SP_0 /*!< PLLI2S division factor for PLLI2SP output by 4 */ +#define LL_RCC_PLLI2SP_DIV_6 RCC_PLLI2SCFGR_PLLI2SP_1 /*!< PLLI2S division factor for PLLI2SP output by 6 */ +#define LL_RCC_PLLI2SP_DIV_8 (RCC_PLLI2SCFGR_PLLI2SP_1 | RCC_PLLI2SCFGR_PLLI2SP_0) /*!< PLLI2S division factor for PLLI2SP output by 8 */ +/** + * @} + */ +#endif /* RCC_PLLI2SCFGR_PLLI2SP */ +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** @defgroup RCC_LL_EC_PLLSAIM PLLSAIM division factor (PLLSAIM or PLLM) + * @{ + */ +#if defined(RCC_PLLSAICFGR_PLLSAIM) +#define LL_RCC_PLLSAIM_DIV_2 (RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 2 */ +#define LL_RCC_PLLSAIM_DIV_3 (RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 3 */ +#define LL_RCC_PLLSAIM_DIV_4 (RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 4 */ +#define LL_RCC_PLLSAIM_DIV_5 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 5 */ +#define LL_RCC_PLLSAIM_DIV_6 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 6 */ +#define LL_RCC_PLLSAIM_DIV_7 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 7 */ +#define LL_RCC_PLLSAIM_DIV_8 (RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 8 */ +#define LL_RCC_PLLSAIM_DIV_9 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 9 */ +#define LL_RCC_PLLSAIM_DIV_10 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 10 */ +#define LL_RCC_PLLSAIM_DIV_11 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 11 */ +#define LL_RCC_PLLSAIM_DIV_12 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 12 */ +#define LL_RCC_PLLSAIM_DIV_13 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 13 */ +#define LL_RCC_PLLSAIM_DIV_14 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 14 */ +#define LL_RCC_PLLSAIM_DIV_15 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 15 */ +#define LL_RCC_PLLSAIM_DIV_16 (RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 16 */ +#define LL_RCC_PLLSAIM_DIV_17 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 17 */ +#define LL_RCC_PLLSAIM_DIV_18 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 18 */ +#define LL_RCC_PLLSAIM_DIV_19 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 19 */ +#define LL_RCC_PLLSAIM_DIV_20 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 20 */ +#define LL_RCC_PLLSAIM_DIV_21 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 21 */ +#define LL_RCC_PLLSAIM_DIV_22 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 22 */ +#define LL_RCC_PLLSAIM_DIV_23 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 23 */ +#define LL_RCC_PLLSAIM_DIV_24 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 24 */ +#define LL_RCC_PLLSAIM_DIV_25 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 25 */ +#define LL_RCC_PLLSAIM_DIV_26 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 26 */ +#define LL_RCC_PLLSAIM_DIV_27 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 27 */ +#define LL_RCC_PLLSAIM_DIV_28 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 28 */ +#define LL_RCC_PLLSAIM_DIV_29 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 29 */ +#define LL_RCC_PLLSAIM_DIV_30 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 30 */ +#define LL_RCC_PLLSAIM_DIV_31 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 31 */ +#define LL_RCC_PLLSAIM_DIV_32 (RCC_PLLSAICFGR_PLLSAIM_5) /*!< PLLSAI division factor for PLLSAIM output by 32 */ +#define LL_RCC_PLLSAIM_DIV_33 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 33 */ +#define LL_RCC_PLLSAIM_DIV_34 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 34 */ +#define LL_RCC_PLLSAIM_DIV_35 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 35 */ +#define LL_RCC_PLLSAIM_DIV_36 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 36 */ +#define LL_RCC_PLLSAIM_DIV_37 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 37 */ +#define LL_RCC_PLLSAIM_DIV_38 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 38 */ +#define LL_RCC_PLLSAIM_DIV_39 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 39 */ +#define LL_RCC_PLLSAIM_DIV_40 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 40 */ +#define LL_RCC_PLLSAIM_DIV_41 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 41 */ +#define LL_RCC_PLLSAIM_DIV_42 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 42 */ +#define LL_RCC_PLLSAIM_DIV_43 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 43 */ +#define LL_RCC_PLLSAIM_DIV_44 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 44 */ +#define LL_RCC_PLLSAIM_DIV_45 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 45 */ +#define LL_RCC_PLLSAIM_DIV_46 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 46 */ +#define LL_RCC_PLLSAIM_DIV_47 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 47 */ +#define LL_RCC_PLLSAIM_DIV_48 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 48 */ +#define LL_RCC_PLLSAIM_DIV_49 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 49 */ +#define LL_RCC_PLLSAIM_DIV_50 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 50 */ +#define LL_RCC_PLLSAIM_DIV_51 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 51 */ +#define LL_RCC_PLLSAIM_DIV_52 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 52 */ +#define LL_RCC_PLLSAIM_DIV_53 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 53 */ +#define LL_RCC_PLLSAIM_DIV_54 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 54 */ +#define LL_RCC_PLLSAIM_DIV_55 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 55 */ +#define LL_RCC_PLLSAIM_DIV_56 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 56 */ +#define LL_RCC_PLLSAIM_DIV_57 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 57 */ +#define LL_RCC_PLLSAIM_DIV_58 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 58 */ +#define LL_RCC_PLLSAIM_DIV_59 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 59 */ +#define LL_RCC_PLLSAIM_DIV_60 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 60 */ +#define LL_RCC_PLLSAIM_DIV_61 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 61 */ +#define LL_RCC_PLLSAIM_DIV_62 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 62 */ +#define LL_RCC_PLLSAIM_DIV_63 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 63 */ +#else +#define LL_RCC_PLLSAIM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLSAI division factor for PLLSAIM output by 2 */ +#define LL_RCC_PLLSAIM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLSAI division factor for PLLSAIM output by 3 */ +#define LL_RCC_PLLSAIM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLSAI division factor for PLLSAIM output by 4 */ +#define LL_RCC_PLLSAIM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLSAI division factor for PLLSAIM output by 5 */ +#define LL_RCC_PLLSAIM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLSAI division factor for PLLSAIM output by 6 */ +#define LL_RCC_PLLSAIM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLSAI division factor for PLLSAIM output by 7 */ +#define LL_RCC_PLLSAIM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLSAI division factor for PLLSAIM output by 8 */ +#define LL_RCC_PLLSAIM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLSAI division factor for PLLSAIM output by 9 */ +#define LL_RCC_PLLSAIM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLSAI division factor for PLLSAIM output by 10 */ +#define LL_RCC_PLLSAIM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLSAI division factor for PLLSAIM output by 11 */ +#define LL_RCC_PLLSAIM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLSAI division factor for PLLSAIM output by 12 */ +#define LL_RCC_PLLSAIM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLSAI division factor for PLLSAIM output by 13 */ +#define LL_RCC_PLLSAIM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLSAI division factor for PLLSAIM output by 14 */ +#define LL_RCC_PLLSAIM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLSAI division factor for PLLSAIM output by 15 */ +#define LL_RCC_PLLSAIM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLSAI division factor for PLLSAIM output by 16 */ +#define LL_RCC_PLLSAIM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLSAI division factor for PLLSAIM output by 17 */ +#define LL_RCC_PLLSAIM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLSAI division factor for PLLSAIM output by 18 */ +#define LL_RCC_PLLSAIM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLSAI division factor for PLLSAIM output by 19 */ +#define LL_RCC_PLLSAIM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLSAI division factor for PLLSAIM output by 20 */ +#define LL_RCC_PLLSAIM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLSAI division factor for PLLSAIM output by 21 */ +#define LL_RCC_PLLSAIM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLSAI division factor for PLLSAIM output by 22 */ +#define LL_RCC_PLLSAIM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLSAI division factor for PLLSAIM output by 23 */ +#define LL_RCC_PLLSAIM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLSAI division factor for PLLSAIM output by 24 */ +#define LL_RCC_PLLSAIM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLSAI division factor for PLLSAIM output by 25 */ +#define LL_RCC_PLLSAIM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLSAI division factor for PLLSAIM output by 26 */ +#define LL_RCC_PLLSAIM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLSAI division factor for PLLSAIM output by 27 */ +#define LL_RCC_PLLSAIM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLSAI division factor for PLLSAIM output by 28 */ +#define LL_RCC_PLLSAIM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLSAI division factor for PLLSAIM output by 29 */ +#define LL_RCC_PLLSAIM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLSAI division factor for PLLSAIM output by 30 */ +#define LL_RCC_PLLSAIM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLSAI division factor for PLLSAIM output by 31 */ +#define LL_RCC_PLLSAIM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLSAI division factor for PLLSAIM output by 32 */ +#define LL_RCC_PLLSAIM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLSAI division factor for PLLSAIM output by 33 */ +#define LL_RCC_PLLSAIM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLSAI division factor for PLLSAIM output by 34 */ +#define LL_RCC_PLLSAIM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLSAI division factor for PLLSAIM output by 35 */ +#define LL_RCC_PLLSAIM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLSAI division factor for PLLSAIM output by 36 */ +#define LL_RCC_PLLSAIM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLSAI division factor for PLLSAIM output by 37 */ +#define LL_RCC_PLLSAIM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLSAI division factor for PLLSAIM output by 38 */ +#define LL_RCC_PLLSAIM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLSAI division factor for PLLSAIM output by 39 */ +#define LL_RCC_PLLSAIM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLSAI division factor for PLLSAIM output by 40 */ +#define LL_RCC_PLLSAIM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLSAI division factor for PLLSAIM output by 41 */ +#define LL_RCC_PLLSAIM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLSAI division factor for PLLSAIM output by 42 */ +#define LL_RCC_PLLSAIM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLSAI division factor for PLLSAIM output by 43 */ +#define LL_RCC_PLLSAIM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLSAI division factor for PLLSAIM output by 44 */ +#define LL_RCC_PLLSAIM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLSAI division factor for PLLSAIM output by 45 */ +#define LL_RCC_PLLSAIM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLSAI division factor for PLLSAIM output by 46 */ +#define LL_RCC_PLLSAIM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLSAI division factor for PLLSAIM output by 47 */ +#define LL_RCC_PLLSAIM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLSAI division factor for PLLSAIM output by 48 */ +#define LL_RCC_PLLSAIM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLSAI division factor for PLLSAIM output by 49 */ +#define LL_RCC_PLLSAIM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLSAI division factor for PLLSAIM output by 50 */ +#define LL_RCC_PLLSAIM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLSAI division factor for PLLSAIM output by 51 */ +#define LL_RCC_PLLSAIM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLSAI division factor for PLLSAIM output by 52 */ +#define LL_RCC_PLLSAIM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLSAI division factor for PLLSAIM output by 53 */ +#define LL_RCC_PLLSAIM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLSAI division factor for PLLSAIM output by 54 */ +#define LL_RCC_PLLSAIM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLSAI division factor for PLLSAIM output by 55 */ +#define LL_RCC_PLLSAIM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLSAI division factor for PLLSAIM output by 56 */ +#define LL_RCC_PLLSAIM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLSAI division factor for PLLSAIM output by 57 */ +#define LL_RCC_PLLSAIM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLSAI division factor for PLLSAIM output by 58 */ +#define LL_RCC_PLLSAIM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLSAI division factor for PLLSAIM output by 59 */ +#define LL_RCC_PLLSAIM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLSAI division factor for PLLSAIM output by 60 */ +#define LL_RCC_PLLSAIM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLSAI division factor for PLLSAIM output by 61 */ +#define LL_RCC_PLLSAIM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLSAI division factor for PLLSAIM output by 62 */ +#define LL_RCC_PLLSAIM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLSAI division factor for PLLSAIM output by 63 */ +#endif /* RCC_PLLSAICFGR_PLLSAIM */ +/** + * @} + */ + +/** @defgroup RCC_LL_EC_PLLSAIQ PLLSAIQ division factor (PLLSAIQ) + * @{ + */ +#define LL_RCC_PLLSAIQ_DIV_2 RCC_PLLSAICFGR_PLLSAIQ_1 /*!< PLLSAI division factor for PLLSAIQ output by 2 */ +#define LL_RCC_PLLSAIQ_DIV_3 (RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 3 */ +#define LL_RCC_PLLSAIQ_DIV_4 RCC_PLLSAICFGR_PLLSAIQ_2 /*!< PLLSAI division factor for PLLSAIQ output by 4 */ +#define LL_RCC_PLLSAIQ_DIV_5 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 5 */ +#define LL_RCC_PLLSAIQ_DIV_6 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 6 */ +#define LL_RCC_PLLSAIQ_DIV_7 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 7 */ +#define LL_RCC_PLLSAIQ_DIV_8 RCC_PLLSAICFGR_PLLSAIQ_3 /*!< PLLSAI division factor for PLLSAIQ output by 8 */ +#define LL_RCC_PLLSAIQ_DIV_9 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 9 */ +#define LL_RCC_PLLSAIQ_DIV_10 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 10 */ +#define LL_RCC_PLLSAIQ_DIV_11 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 11 */ +#define LL_RCC_PLLSAIQ_DIV_12 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2) /*!< PLLSAI division factor for PLLSAIQ output by 12 */ +#define LL_RCC_PLLSAIQ_DIV_13 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 13 */ +#define LL_RCC_PLLSAIQ_DIV_14 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 14 */ +#define LL_RCC_PLLSAIQ_DIV_15 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 15 */ +/** + * @} + */ + +#if defined(RCC_DCKCFGR_PLLSAIDIVQ) +/** @defgroup RCC_LL_EC_PLLSAIDIVQ PLLSAIDIVQ division factor (PLLSAIDIVQ) + * @{ + */ +#define LL_RCC_PLLSAIDIVQ_DIV_1 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVQ output by 1 */ +#define LL_RCC_PLLSAIDIVQ_DIV_2 RCC_DCKCFGR_PLLSAIDIVQ_0 /*!< PLLSAI division factor for PLLSAIDIVQ output by 2 */ +#define LL_RCC_PLLSAIDIVQ_DIV_3 RCC_DCKCFGR_PLLSAIDIVQ_1 /*!< PLLSAI division factor for PLLSAIDIVQ output by 3 */ +#define LL_RCC_PLLSAIDIVQ_DIV_4 (RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 4 */ +#define LL_RCC_PLLSAIDIVQ_DIV_5 RCC_DCKCFGR_PLLSAIDIVQ_2 /*!< PLLSAI division factor for PLLSAIDIVQ output by 5 */ +#define LL_RCC_PLLSAIDIVQ_DIV_6 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 6 */ +#define LL_RCC_PLLSAIDIVQ_DIV_7 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 7 */ +#define LL_RCC_PLLSAIDIVQ_DIV_8 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 8 */ +#define LL_RCC_PLLSAIDIVQ_DIV_9 RCC_DCKCFGR_PLLSAIDIVQ_3 /*!< PLLSAI division factor for PLLSAIDIVQ output by 9 */ +#define LL_RCC_PLLSAIDIVQ_DIV_10 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 10 */ +#define LL_RCC_PLLSAIDIVQ_DIV_11 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 11 */ +#define LL_RCC_PLLSAIDIVQ_DIV_12 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 12 */ +#define LL_RCC_PLLSAIDIVQ_DIV_13 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 13 */ +#define LL_RCC_PLLSAIDIVQ_DIV_14 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 14 */ +#define LL_RCC_PLLSAIDIVQ_DIV_15 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 15 */ +#define LL_RCC_PLLSAIDIVQ_DIV_16 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 16 */ +#define LL_RCC_PLLSAIDIVQ_DIV_17 RCC_DCKCFGR_PLLSAIDIVQ_4 /*!< PLLSAI division factor for PLLSAIDIVQ output by 17 */ +#define LL_RCC_PLLSAIDIVQ_DIV_18 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 18 */ +#define LL_RCC_PLLSAIDIVQ_DIV_19 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 19 */ +#define LL_RCC_PLLSAIDIVQ_DIV_20 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 20 */ +#define LL_RCC_PLLSAIDIVQ_DIV_21 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 21 */ +#define LL_RCC_PLLSAIDIVQ_DIV_22 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 22 */ +#define LL_RCC_PLLSAIDIVQ_DIV_23 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 23 */ +#define LL_RCC_PLLSAIDIVQ_DIV_24 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 24 */ +#define LL_RCC_PLLSAIDIVQ_DIV_25 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3) /*!< PLLSAI division factor for PLLSAIDIVQ output by 25 */ +#define LL_RCC_PLLSAIDIVQ_DIV_26 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 26 */ +#define LL_RCC_PLLSAIDIVQ_DIV_27 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 27 */ +#define LL_RCC_PLLSAIDIVQ_DIV_28 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 28 */ +#define LL_RCC_PLLSAIDIVQ_DIV_29 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 29 */ +#define LL_RCC_PLLSAIDIVQ_DIV_30 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 30 */ +#define LL_RCC_PLLSAIDIVQ_DIV_31 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 31 */ +#define LL_RCC_PLLSAIDIVQ_DIV_32 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 32 */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_PLLSAIDIVQ */ + +#if defined(RCC_PLLSAICFGR_PLLSAIR) +/** @defgroup RCC_LL_EC_PLLSAIR PLLSAIR division factor (PLLSAIR) + * @{ + */ +#define LL_RCC_PLLSAIR_DIV_2 RCC_PLLSAICFGR_PLLSAIR_1 /*!< PLLSAI division factor for PLLSAIR output by 2 */ +#define LL_RCC_PLLSAIR_DIV_3 (RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 3 */ +#define LL_RCC_PLLSAIR_DIV_4 RCC_PLLSAICFGR_PLLSAIR_2 /*!< PLLSAI division factor for PLLSAIR output by 4 */ +#define LL_RCC_PLLSAIR_DIV_5 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 5 */ +#define LL_RCC_PLLSAIR_DIV_6 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1) /*!< PLLSAI division factor for PLLSAIR output by 6 */ +#define LL_RCC_PLLSAIR_DIV_7 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 7 */ +/** + * @} + */ +#endif /* RCC_PLLSAICFGR_PLLSAIR */ + +#if defined(RCC_DCKCFGR_PLLSAIDIVR) +/** @defgroup RCC_LL_EC_PLLSAIDIVR PLLSAIDIVR division factor (PLLSAIDIVR) + * @{ + */ +#define LL_RCC_PLLSAIDIVR_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVR output by 2 */ +#define LL_RCC_PLLSAIDIVR_DIV_4 RCC_DCKCFGR_PLLSAIDIVR_0 /*!< PLLSAI division factor for PLLSAIDIVR output by 4 */ +#define LL_RCC_PLLSAIDIVR_DIV_8 RCC_DCKCFGR_PLLSAIDIVR_1 /*!< PLLSAI division factor for PLLSAIDIVR output by 8 */ +#define LL_RCC_PLLSAIDIVR_DIV_16 (RCC_DCKCFGR_PLLSAIDIVR_1 | RCC_DCKCFGR_PLLSAIDIVR_0) /*!< PLLSAI division factor for PLLSAIDIVR output by 16 */ +/** + * @} + */ +#endif /* RCC_DCKCFGR_PLLSAIDIVR */ + +#if defined(RCC_PLLSAICFGR_PLLSAIP) +/** @defgroup RCC_LL_EC_PLLSAIP PLLSAIP division factor (PLLSAIP) + * @{ + */ +#define LL_RCC_PLLSAIP_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIP output by 2 */ +#define LL_RCC_PLLSAIP_DIV_4 RCC_PLLSAICFGR_PLLSAIP_0 /*!< PLLSAI division factor for PLLSAIP output by 4 */ +#define LL_RCC_PLLSAIP_DIV_6 RCC_PLLSAICFGR_PLLSAIP_1 /*!< PLLSAI division factor for PLLSAIP output by 6 */ +#define LL_RCC_PLLSAIP_DIV_8 (RCC_PLLSAICFGR_PLLSAIP_1 | RCC_PLLSAICFGR_PLLSAIP_0) /*!< PLLSAI division factor for PLLSAIP output by 8 */ +/** + * @} + */ +#endif /* RCC_PLLSAICFGR_PLLSAIP */ +#endif /* RCC_PLLSAI_SUPPORT */ +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup RCC_LL_Exported_Macros RCC Exported Macros + * @{ + */ + +/** @defgroup RCC_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in RCC register + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_RCC_WriteReg(__REG__, __VALUE__) WRITE_REG(RCC->__REG__, (__VALUE__)) + +/** + * @brief Read a value in RCC register + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_RCC_ReadReg(__REG__) READ_REG(RCC->__REG__) +/** + * @} + */ + +/** @defgroup RCC_LL_EM_CALC_FREQ Calculate frequencies + * @{ + */ + +/** + * @brief Helper macro to calculate the PLLCLK frequency on system domain + * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetP ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLP__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLP_DIV_2 + * @arg @ref LL_RCC_PLLP_DIV_4 + * @arg @ref LL_RCC_PLLP_DIV_6 + * @arg @ref LL_RCC_PLLP_DIV_8 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLP__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((((__PLLP__) >> RCC_PLLCFGR_PLLP_Pos ) + 1U) * 2U)) + +#if defined(RCC_PLLR_SYSCLK_SUPPORT) +/** + * @brief Helper macro to calculate the PLLRCLK frequency on system domain + * @note ex: @ref __LL_RCC_CALC_PLLRCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50 and 432 + * @param __PLLR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLRCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) + +#endif /* RCC_PLLR_SYSCLK_SUPPORT */ + +/** + * @brief Helper macro to calculate the PLLCLK frequency used on 48M domain + * @note ex: @ref __LL_RCC_CALC_PLLCLK_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetQ ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLQ__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLQ_DIV_2 + * @arg @ref LL_RCC_PLLQ_DIV_3 + * @arg @ref LL_RCC_PLLQ_DIV_4 + * @arg @ref LL_RCC_PLLQ_DIV_5 + * @arg @ref LL_RCC_PLLQ_DIV_6 + * @arg @ref LL_RCC_PLLQ_DIV_7 + * @arg @ref LL_RCC_PLLQ_DIV_8 + * @arg @ref LL_RCC_PLLQ_DIV_9 + * @arg @ref LL_RCC_PLLQ_DIV_10 + * @arg @ref LL_RCC_PLLQ_DIV_11 + * @arg @ref LL_RCC_PLLQ_DIV_12 + * @arg @ref LL_RCC_PLLQ_DIV_13 + * @arg @ref LL_RCC_PLLQ_DIV_14 + * @arg @ref LL_RCC_PLLQ_DIV_15 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLCLK_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLQ__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLQ__) >> RCC_PLLCFGR_PLLQ_Pos )) + +#if defined(DSI) +/** + * @brief Helper macro to calculate the PLLCLK frequency used on DSI + * @note ex: @ref __LL_RCC_CALC_PLLCLK_DSI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50 and 432 + * @param __PLLR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLCLK_DSI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) +#endif /* DSI */ + +#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) +/** + * @brief Helper macro to calculate the PLLCLK frequency used on I2S + * @note ex: @ref __LL_RCC_CALC_PLLCLK_I2S_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50 and 432 + * @param __PLLR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLCLK_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) +#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ + +#if defined(SPDIFRX) +/** + * @brief Helper macro to calculate the PLLCLK frequency used on SPDIFRX + * @note ex: @ref __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50 and 432 + * @param __PLLR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval PLL clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) +#endif /* SPDIFRX */ + +#if defined(RCC_PLLCFGR_PLLR) +#if defined(SAI1) +/** + * @brief Helper macro to calculate the PLLCLK frequency used on SAI + * @note ex: @ref __LL_RCC_CALC_PLLCLK_SAI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), + * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR (), @ref LL_RCC_PLL_GetDIVR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param __PLLN__ Between 50 and 432 + * @param __PLLR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @param __PLLDIVR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) + * + * (*) value not defined in all devices. + * @retval PLL clock frequency (in Hz) + */ +#if defined(RCC_DCKCFGR_PLLDIVR) +#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__, __PLLDIVR__) (((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) / ((__PLLDIVR__) >> RCC_DCKCFGR_PLLDIVR_Pos )) +#else +#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ + ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) +#endif /* RCC_DCKCFGR_PLLDIVR */ +#endif /* SAI1 */ +#endif /* RCC_PLLCFGR_PLLR */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Helper macro to calculate the PLLSAI frequency used for SAI domain + * @note ex: @ref __LL_RCC_CALC_PLLSAI_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), + * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetQ (), @ref LL_RCC_PLLSAI_GetDIVQ ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param __PLLSAIN__ Between 49/50(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLSAIQ__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIQ_DIV_15 + * @param __PLLSAIDIVQ__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 + * @retval PLLSAI clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLSAI_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIQ__, __PLLSAIDIVQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ + (((__PLLSAIQ__) >> RCC_PLLSAICFGR_PLLSAIQ_Pos) * (((__PLLSAIDIVQ__) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos) + 1U))) + +#if defined(RCC_PLLSAICFGR_PLLSAIP) +/** + * @brief Helper macro to calculate the PLLSAI frequency used on 48Mhz domain + * @note ex: @ref __LL_RCC_CALC_PLLSAI_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), + * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetP ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param __PLLSAIN__ Between 50 and 432 + * @param __PLLSAIP__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIP_DIV_2 + * @arg @ref LL_RCC_PLLSAIP_DIV_4 + * @arg @ref LL_RCC_PLLSAIP_DIV_6 + * @arg @ref LL_RCC_PLLSAIP_DIV_8 + * @retval PLLSAI clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLSAI_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ + ((((__PLLSAIP__) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) * 2U)) +#endif /* RCC_PLLSAICFGR_PLLSAIP */ + +#if defined(LTDC) +/** + * @brief Helper macro to calculate the PLLSAI frequency used for LTDC domain + * @note ex: @ref __LL_RCC_CALC_PLLSAI_LTDC_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), + * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetR (), @ref LL_RCC_PLLSAI_GetDIVR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param __PLLSAIN__ Between 49/50(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLSAIR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIR_DIV_2 + * @arg @ref LL_RCC_PLLSAIR_DIV_3 + * @arg @ref LL_RCC_PLLSAIR_DIV_4 + * @arg @ref LL_RCC_PLLSAIR_DIV_5 + * @arg @ref LL_RCC_PLLSAIR_DIV_6 + * @arg @ref LL_RCC_PLLSAIR_DIV_7 + * @param __PLLSAIDIVR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 + * @retval PLLSAI clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLSAI_LTDC_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIR__, __PLLSAIDIVR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ + (((__PLLSAIR__) >> RCC_PLLSAICFGR_PLLSAIR_Pos) * (aRCC_PLLSAIDIVRPrescTable[(__PLLSAIDIVR__) >> RCC_DCKCFGR_PLLSAIDIVR_Pos]))) +#endif /* LTDC */ +#endif /* RCC_PLLSAI_SUPPORT */ + +#if defined(RCC_PLLI2S_SUPPORT) +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR) +/** + * @brief Helper macro to calculate the PLLI2S frequency used for SAI domain + * @note ex: @ref __LL_RCC_CALC_PLLI2S_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), + * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ (), @ref LL_RCC_PLLI2S_GetDIVQ ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param __PLLI2SN__ Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLI2SQ_R__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) + * + * (*) value not defined in all devices. + * @param __PLLI2SDIVQ_R__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) + * + * (*) value not defined in all devices. + * @retval PLLI2S clock frequency (in Hz) + */ +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) +#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ + (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos) * (((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos) + 1U))) +#else +#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ + (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos) * ((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVR_Pos))) + +#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ +#endif /* RCC_DCKCFGR_PLLI2SDIVQ || RCC_DCKCFGR_PLLI2SDIVR */ + +#if defined(SPDIFRX) +/** + * @brief Helper macro to calculate the PLLI2S frequency used on SPDIFRX domain + * @note ex: @ref __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), + * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetP ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param __PLLI2SN__ Between 50 and 432 + * @param __PLLI2SP__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SP_DIV_2 + * @arg @ref LL_RCC_PLLI2SP_DIV_4 + * @arg @ref LL_RCC_PLLI2SP_DIV_6 + * @arg @ref LL_RCC_PLLI2SP_DIV_8 + * @retval PLLI2S clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ + ((((__PLLI2SP__) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) * 2U)) + +#endif /* SPDIFRX */ + +/** + * @brief Helper macro to calculate the PLLI2S frequency used for I2S domain + * @note ex: @ref __LL_RCC_CALC_PLLI2S_I2S_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), + * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetR ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param __PLLI2SN__ Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param __PLLI2SR__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SR_DIV_2 + * @arg @ref LL_RCC_PLLI2SR_DIV_3 + * @arg @ref LL_RCC_PLLI2SR_DIV_4 + * @arg @ref LL_RCC_PLLI2SR_DIV_5 + * @arg @ref LL_RCC_PLLI2SR_DIV_6 + * @arg @ref LL_RCC_PLLI2SR_DIV_7 + * @retval PLLI2S clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLI2S_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ + ((__PLLI2SR__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos)) + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +/** + * @brief Helper macro to calculate the PLLI2S frequency used for 48Mhz domain + * @note ex: @ref __LL_RCC_CALC_PLLI2S_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), + * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ ()); + * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) + * @param __PLLM__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param __PLLI2SN__ Between 50 and 432 + * @param __PLLI2SQ__ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SQ_DIV_2 + * @arg @ref LL_RCC_PLLI2SQ_DIV_3 + * @arg @ref LL_RCC_PLLI2SQ_DIV_4 + * @arg @ref LL_RCC_PLLI2SQ_DIV_5 + * @arg @ref LL_RCC_PLLI2SQ_DIV_6 + * @arg @ref LL_RCC_PLLI2SQ_DIV_7 + * @arg @ref LL_RCC_PLLI2SQ_DIV_8 + * @arg @ref LL_RCC_PLLI2SQ_DIV_9 + * @arg @ref LL_RCC_PLLI2SQ_DIV_10 + * @arg @ref LL_RCC_PLLI2SQ_DIV_11 + * @arg @ref LL_RCC_PLLI2SQ_DIV_12 + * @arg @ref LL_RCC_PLLI2SQ_DIV_13 + * @arg @ref LL_RCC_PLLI2SQ_DIV_14 + * @arg @ref LL_RCC_PLLI2SQ_DIV_15 + * @retval PLLI2S clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PLLI2S_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ + ((__PLLI2SQ__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos)) + +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +#endif /* RCC_PLLI2S_SUPPORT */ + +/** + * @brief Helper macro to calculate the HCLK frequency + * @param __SYSCLKFREQ__ SYSCLK frequency (based on HSE/HSI/PLLCLK) + * @param __AHBPRESCALER__ This parameter can be one of the following values: + * @arg @ref LL_RCC_SYSCLK_DIV_1 + * @arg @ref LL_RCC_SYSCLK_DIV_2 + * @arg @ref LL_RCC_SYSCLK_DIV_4 + * @arg @ref LL_RCC_SYSCLK_DIV_8 + * @arg @ref LL_RCC_SYSCLK_DIV_16 + * @arg @ref LL_RCC_SYSCLK_DIV_64 + * @arg @ref LL_RCC_SYSCLK_DIV_128 + * @arg @ref LL_RCC_SYSCLK_DIV_256 + * @arg @ref LL_RCC_SYSCLK_DIV_512 + * @retval HCLK clock frequency (in Hz) + */ +#define __LL_RCC_CALC_HCLK_FREQ(__SYSCLKFREQ__, __AHBPRESCALER__) ((__SYSCLKFREQ__) >> AHBPrescTable[((__AHBPRESCALER__) & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos]) + +/** + * @brief Helper macro to calculate the PCLK1 frequency (ABP1) + * @param __HCLKFREQ__ HCLK frequency + * @param __APB1PRESCALER__ This parameter can be one of the following values: + * @arg @ref LL_RCC_APB1_DIV_1 + * @arg @ref LL_RCC_APB1_DIV_2 + * @arg @ref LL_RCC_APB1_DIV_4 + * @arg @ref LL_RCC_APB1_DIV_8 + * @arg @ref LL_RCC_APB1_DIV_16 + * @retval PCLK1 clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PCLK1_FREQ(__HCLKFREQ__, __APB1PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB1PRESCALER__) >> RCC_CFGR_PPRE1_Pos]) + +/** + * @brief Helper macro to calculate the PCLK2 frequency (ABP2) + * @param __HCLKFREQ__ HCLK frequency + * @param __APB2PRESCALER__ This parameter can be one of the following values: + * @arg @ref LL_RCC_APB2_DIV_1 + * @arg @ref LL_RCC_APB2_DIV_2 + * @arg @ref LL_RCC_APB2_DIV_4 + * @arg @ref LL_RCC_APB2_DIV_8 + * @arg @ref LL_RCC_APB2_DIV_16 + * @retval PCLK2 clock frequency (in Hz) + */ +#define __LL_RCC_CALC_PCLK2_FREQ(__HCLKFREQ__, __APB2PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB2PRESCALER__) >> RCC_CFGR_PPRE2_Pos]) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup RCC_LL_Exported_Functions RCC Exported Functions + * @{ + */ + +/** @defgroup RCC_LL_EF_HSE HSE + * @{ + */ + +/** + * @brief Enable the Clock Security System. + * @rmtoll CR CSSON LL_RCC_HSE_EnableCSS + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSE_EnableCSS(void) +{ + SET_BIT(RCC->CR, RCC_CR_CSSON); +} + +/** + * @brief Enable HSE external oscillator (HSE Bypass) + * @rmtoll CR HSEBYP LL_RCC_HSE_EnableBypass + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSE_EnableBypass(void) +{ + SET_BIT(RCC->CR, RCC_CR_HSEBYP); +} + +/** + * @brief Disable HSE external oscillator (HSE Bypass) + * @rmtoll CR HSEBYP LL_RCC_HSE_DisableBypass + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSE_DisableBypass(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); +} + +/** + * @brief Enable HSE crystal oscillator (HSE ON) + * @rmtoll CR HSEON LL_RCC_HSE_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSE_Enable(void) +{ + SET_BIT(RCC->CR, RCC_CR_HSEON); +} + +/** + * @brief Disable HSE crystal oscillator (HSE ON) + * @rmtoll CR HSEON LL_RCC_HSE_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSE_Disable(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_HSEON); +} + +/** + * @brief Check if HSE oscillator Ready + * @rmtoll CR HSERDY LL_RCC_HSE_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_HSE_IsReady(void) +{ + return (READ_BIT(RCC->CR, RCC_CR_HSERDY) == (RCC_CR_HSERDY)); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_HSI HSI + * @{ + */ + +/** + * @brief Enable HSI oscillator + * @rmtoll CR HSION LL_RCC_HSI_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSI_Enable(void) +{ + SET_BIT(RCC->CR, RCC_CR_HSION); +} + +/** + * @brief Disable HSI oscillator + * @rmtoll CR HSION LL_RCC_HSI_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSI_Disable(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_HSION); +} + +/** + * @brief Check if HSI clock is ready + * @rmtoll CR HSIRDY LL_RCC_HSI_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_HSI_IsReady(void) +{ + return (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == (RCC_CR_HSIRDY)); +} + +/** + * @brief Get HSI Calibration value + * @note When HSITRIM is written, HSICAL is updated with the sum of + * HSITRIM and the factory trim value + * @rmtoll CR HSICAL LL_RCC_HSI_GetCalibration + * @retval Between Min_Data = 0x00 and Max_Data = 0xFF + */ +__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibration(void) +{ + return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSICAL) >> RCC_CR_HSICAL_Pos); +} + +/** + * @brief Set HSI Calibration trimming + * @note user-programmable trimming value that is added to the HSICAL + * @note Default value is 16, which, when added to the HSICAL value, + * should trim the HSI to 16 MHz +/- 1 % + * @rmtoll CR HSITRIM LL_RCC_HSI_SetCalibTrimming + * @param Value Between Min_Data = 0 and Max_Data = 31 + * @retval None + */ +__STATIC_INLINE void LL_RCC_HSI_SetCalibTrimming(uint32_t Value) +{ + MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, Value << RCC_CR_HSITRIM_Pos); +} + +/** + * @brief Get HSI Calibration trimming + * @rmtoll CR HSITRIM LL_RCC_HSI_GetCalibTrimming + * @retval Between Min_Data = 0 and Max_Data = 31 + */ +__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibTrimming(void) +{ + return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_LSE LSE + * @{ + */ + +/** + * @brief Enable Low Speed External (LSE) crystal. + * @rmtoll BDCR LSEON LL_RCC_LSE_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_Enable(void) +{ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); +} + +/** + * @brief Disable Low Speed External (LSE) crystal. + * @rmtoll BDCR LSEON LL_RCC_LSE_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_Disable(void) +{ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); +} + +/** + * @brief Enable external clock source (LSE bypass). + * @rmtoll BDCR LSEBYP LL_RCC_LSE_EnableBypass + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_EnableBypass(void) +{ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); +} + +/** + * @brief Disable external clock source (LSE bypass). + * @rmtoll BDCR LSEBYP LL_RCC_LSE_DisableBypass + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_DisableBypass(void) +{ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); +} + +/** + * @brief Check if LSE oscillator Ready + * @rmtoll BDCR LSERDY LL_RCC_LSE_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_LSE_IsReady(void) +{ + return (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == (RCC_BDCR_LSERDY)); +} + +#if defined(RCC_BDCR_LSEMOD) +/** + * @brief Enable LSE high drive mode. + * @note LSE high drive mode can be enabled only when the LSE clock is disabled + * @rmtoll BDCR LSEMOD LL_RCC_LSE_EnableHighDriveMode + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_EnableHighDriveMode(void) +{ + SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); +} + +/** + * @brief Disable LSE high drive mode. + * @note LSE high drive mode can be disabled only when the LSE clock is disabled + * @rmtoll BDCR LSEMOD LL_RCC_LSE_DisableHighDriveMode + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSE_DisableHighDriveMode(void) +{ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); +} +#endif /* RCC_BDCR_LSEMOD */ + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_LSI LSI + * @{ + */ + +/** + * @brief Enable LSI Oscillator + * @rmtoll CSR LSION LL_RCC_LSI_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSI_Enable(void) +{ + SET_BIT(RCC->CSR, RCC_CSR_LSION); +} + +/** + * @brief Disable LSI Oscillator + * @rmtoll CSR LSION LL_RCC_LSI_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_LSI_Disable(void) +{ + CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); +} + +/** + * @brief Check if LSI is Ready + * @rmtoll CSR LSIRDY LL_RCC_LSI_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_LSI_IsReady(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == (RCC_CSR_LSIRDY)); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_System System + * @{ + */ + +/** + * @brief Configure the system clock source + * @rmtoll CFGR SW LL_RCC_SetSysClkSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI + * @arg @ref LL_RCC_SYS_CLKSOURCE_HSE + * @arg @ref LL_RCC_SYS_CLKSOURCE_PLL + * @arg @ref LL_RCC_SYS_CLKSOURCE_PLLR (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetSysClkSource(uint32_t Source) +{ + MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, Source); +} + +/** + * @brief Get the system clock source + * @rmtoll CFGR SWS LL_RCC_GetSysClkSource + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI + * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSE + * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLL + * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLLR (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetSysClkSource(void) +{ + return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_SWS)); +} + +/** + * @brief Set AHB prescaler + * @rmtoll CFGR HPRE LL_RCC_SetAHBPrescaler + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_SYSCLK_DIV_1 + * @arg @ref LL_RCC_SYSCLK_DIV_2 + * @arg @ref LL_RCC_SYSCLK_DIV_4 + * @arg @ref LL_RCC_SYSCLK_DIV_8 + * @arg @ref LL_RCC_SYSCLK_DIV_16 + * @arg @ref LL_RCC_SYSCLK_DIV_64 + * @arg @ref LL_RCC_SYSCLK_DIV_128 + * @arg @ref LL_RCC_SYSCLK_DIV_256 + * @arg @ref LL_RCC_SYSCLK_DIV_512 + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetAHBPrescaler(uint32_t Prescaler) +{ + MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, Prescaler); +} + +/** + * @brief Set APB1 prescaler + * @rmtoll CFGR PPRE1 LL_RCC_SetAPB1Prescaler + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_APB1_DIV_1 + * @arg @ref LL_RCC_APB1_DIV_2 + * @arg @ref LL_RCC_APB1_DIV_4 + * @arg @ref LL_RCC_APB1_DIV_8 + * @arg @ref LL_RCC_APB1_DIV_16 + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetAPB1Prescaler(uint32_t Prescaler) +{ + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, Prescaler); +} + +/** + * @brief Set APB2 prescaler + * @rmtoll CFGR PPRE2 LL_RCC_SetAPB2Prescaler + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_APB2_DIV_1 + * @arg @ref LL_RCC_APB2_DIV_2 + * @arg @ref LL_RCC_APB2_DIV_4 + * @arg @ref LL_RCC_APB2_DIV_8 + * @arg @ref LL_RCC_APB2_DIV_16 + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetAPB2Prescaler(uint32_t Prescaler) +{ + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, Prescaler); +} + +/** + * @brief Get AHB prescaler + * @rmtoll CFGR HPRE LL_RCC_GetAHBPrescaler + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SYSCLK_DIV_1 + * @arg @ref LL_RCC_SYSCLK_DIV_2 + * @arg @ref LL_RCC_SYSCLK_DIV_4 + * @arg @ref LL_RCC_SYSCLK_DIV_8 + * @arg @ref LL_RCC_SYSCLK_DIV_16 + * @arg @ref LL_RCC_SYSCLK_DIV_64 + * @arg @ref LL_RCC_SYSCLK_DIV_128 + * @arg @ref LL_RCC_SYSCLK_DIV_256 + * @arg @ref LL_RCC_SYSCLK_DIV_512 + */ +__STATIC_INLINE uint32_t LL_RCC_GetAHBPrescaler(void) +{ + return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_HPRE)); +} + +/** + * @brief Get APB1 prescaler + * @rmtoll CFGR PPRE1 LL_RCC_GetAPB1Prescaler + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_APB1_DIV_1 + * @arg @ref LL_RCC_APB1_DIV_2 + * @arg @ref LL_RCC_APB1_DIV_4 + * @arg @ref LL_RCC_APB1_DIV_8 + * @arg @ref LL_RCC_APB1_DIV_16 + */ +__STATIC_INLINE uint32_t LL_RCC_GetAPB1Prescaler(void) +{ + return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1)); +} + +/** + * @brief Get APB2 prescaler + * @rmtoll CFGR PPRE2 LL_RCC_GetAPB2Prescaler + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_APB2_DIV_1 + * @arg @ref LL_RCC_APB2_DIV_2 + * @arg @ref LL_RCC_APB2_DIV_4 + * @arg @ref LL_RCC_APB2_DIV_8 + * @arg @ref LL_RCC_APB2_DIV_16 + */ +__STATIC_INLINE uint32_t LL_RCC_GetAPB2Prescaler(void) +{ + return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2)); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_MCO MCO + * @{ + */ + +#if defined(RCC_CFGR_MCO1EN) +/** + * @brief Enable MCO1 output + * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_MCO1_Enable(void) +{ + SET_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); +} + +/** + * @brief Disable MCO1 output + * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_MCO1_Disable(void) +{ + CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); +} +#endif /* RCC_CFGR_MCO1EN */ + +#if defined(RCC_CFGR_MCO2EN) +/** + * @brief Enable MCO2 output + * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_MCO2_Enable(void) +{ + SET_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); +} + +/** + * @brief Disable MCO2 output + * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_MCO2_Disable(void) +{ + CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); +} +#endif /* RCC_CFGR_MCO2EN */ + +/** + * @brief Configure MCOx + * @rmtoll CFGR MCO1 LL_RCC_ConfigMCO\n + * CFGR MCO1PRE LL_RCC_ConfigMCO\n + * CFGR MCO2 LL_RCC_ConfigMCO\n + * CFGR MCO2PRE LL_RCC_ConfigMCO + * @param MCOxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_MCO1SOURCE_HSI + * @arg @ref LL_RCC_MCO1SOURCE_LSE + * @arg @ref LL_RCC_MCO1SOURCE_HSE + * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK + * @arg @ref LL_RCC_MCO2SOURCE_SYSCLK + * @arg @ref LL_RCC_MCO2SOURCE_PLLI2S + * @arg @ref LL_RCC_MCO2SOURCE_HSE + * @arg @ref LL_RCC_MCO2SOURCE_PLLCLK + * @param MCOxPrescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_MCO1_DIV_1 + * @arg @ref LL_RCC_MCO1_DIV_2 + * @arg @ref LL_RCC_MCO1_DIV_3 + * @arg @ref LL_RCC_MCO1_DIV_4 + * @arg @ref LL_RCC_MCO1_DIV_5 + * @arg @ref LL_RCC_MCO2_DIV_1 + * @arg @ref LL_RCC_MCO2_DIV_2 + * @arg @ref LL_RCC_MCO2_DIV_3 + * @arg @ref LL_RCC_MCO2_DIV_4 + * @arg @ref LL_RCC_MCO2_DIV_5 + * @retval None + */ +__STATIC_INLINE void LL_RCC_ConfigMCO(uint32_t MCOxSource, uint32_t MCOxPrescaler) +{ + MODIFY_REG(RCC->CFGR, (MCOxSource & 0xFFFF0000U) | (MCOxPrescaler & 0xFFFF0000U), (MCOxSource << 16U) | (MCOxPrescaler << 16U)); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_Peripheral_Clock_Source Peripheral Clock Source + * @{ + */ +#if defined(FMPI2C1) +/** + * @brief Configure FMPI2C clock source + * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_SetFMPI2CClockSource + * @param FMPI2CxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetFMPI2CClockSource(uint32_t FMPI2CxSource) +{ + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, FMPI2CxSource); +} +#endif /* FMPI2C1 */ + +#if defined(LPTIM1) +/** + * @brief Configure LPTIMx clock source + * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_SetLPTIMClockSource + * @param LPTIMxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetLPTIMClockSource(uint32_t LPTIMxSource) +{ + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, LPTIMxSource); +} +#endif /* LPTIM1 */ + +#if defined(SAI1) +/** + * @brief Configure SAIx clock source + * @rmtoll DCKCFGR SAI1SRC LL_RCC_SetSAIClockSource\n + * DCKCFGR SAI2SRC LL_RCC_SetSAIClockSource\n + * DCKCFGR SAI1ASRC LL_RCC_SetSAIClockSource\n + * DCKCFGR SAI1BSRC LL_RCC_SetSAIClockSource + * @param SAIxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetSAIClockSource(uint32_t SAIxSource) +{ + MODIFY_REG(RCC->DCKCFGR, (SAIxSource & 0xFFFF0000U), (SAIxSource << 16U)); +} +#endif /* SAI1 */ + +#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) +/** + * @brief Configure SDIO clock source + * @rmtoll DCKCFGR SDIOSEL LL_RCC_SetSDIOClockSource\n + * DCKCFGR2 SDIOSEL LL_RCC_SetSDIOClockSource + * @param SDIOxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK + * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetSDIOClockSource(uint32_t SDIOxSource) +{ +#if defined(RCC_DCKCFGR_SDIOSEL) + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, SDIOxSource); +#else + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, SDIOxSource); +#endif /* RCC_DCKCFGR_SDIOSEL */ +} +#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +/** + * @brief Configure 48Mhz domain clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetCK48MClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_SetCK48MClockSource + * @param CK48MxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetCK48MClockSource(uint32_t CK48MxSource) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, CK48MxSource); +#else + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, CK48MxSource); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} + +#if defined(RNG) +/** + * @brief Configure RNG clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetRNGClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_SetRNGClockSource + * @param RNGxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetRNGClockSource(uint32_t RNGxSource) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, RNGxSource); +#else + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, RNGxSource); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} +#endif /* RNG */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +/** + * @brief Configure USB clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetUSBClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_SetUSBClockSource + * @param USBxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_USB_CLKSOURCE_PLL + * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetUSBClockSource(uint32_t USBxSource) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, USBxSource); +#else + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, USBxSource); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} +#endif /* USB_OTG_FS || USB_OTG_HS */ +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + +#if defined(CEC) +/** + * @brief Configure CEC clock source + * @rmtoll DCKCFGR2 CECSEL LL_RCC_SetCECClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 + * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetCECClockSource(uint32_t Source) +{ + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, Source); +} +#endif /* CEC */ + +/** + * @brief Configure I2S clock source + * @rmtoll CFGR I2SSRC LL_RCC_SetI2SClockSource\n + * DCKCFGR I2SSRC LL_RCC_SetI2SClockSource\n + * DCKCFGR I2S1SRC LL_RCC_SetI2SClockSource\n + * DCKCFGR I2S2SRC LL_RCC_SetI2SClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetI2SClockSource(uint32_t Source) +{ +#if defined(RCC_CFGR_I2SSRC) + MODIFY_REG(RCC->CFGR, RCC_CFGR_I2SSRC, Source); +#else + MODIFY_REG(RCC->DCKCFGR, (Source & 0xFFFF0000U), (Source << 16U)); +#endif /* RCC_CFGR_I2SSRC */ +} + +#if defined(DSI) +/** + * @brief Configure DSI clock source + * @rmtoll DCKCFGR DSISEL LL_RCC_SetDSIClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY + * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetDSIClockSource(uint32_t Source) +{ + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, Source); +} +#endif /* DSI */ + +#if defined(DFSDM1_Channel0) +/** + * @brief Configure DFSDM Audio clock source + * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_SetDFSDMAudioClockSource\n + * DCKCFGR CKDFSDM2ASEL LL_RCC_SetDFSDMAudioClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetDFSDMAudioClockSource(uint32_t Source) +{ + MODIFY_REG(RCC->DCKCFGR, (Source & 0x0000FFFFU), (Source >> 16U)); +} + +/** + * @brief Configure DFSDM Kernel clock source + * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_SetDFSDMClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetDFSDMClockSource(uint32_t Source) +{ + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, Source); +} +#endif /* DFSDM1_Channel0 */ + +#if defined(SPDIFRX) +/** + * @brief Configure SPDIFRX clock source + * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_SetSPDIFRXClockSource + * @param SPDIFRXxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetSPDIFRXClockSource(uint32_t SPDIFRXxSource) +{ + MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, SPDIFRXxSource); +} +#endif /* SPDIFRX */ + +#if defined(FMPI2C1) +/** + * @brief Get FMPI2C clock source + * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_GetFMPI2CClockSource + * @param FMPI2Cx This parameter can be one of the following values: + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI + */ +__STATIC_INLINE uint32_t LL_RCC_GetFMPI2CClockSource(uint32_t FMPI2Cx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, FMPI2Cx)); +} +#endif /* FMPI2C1 */ + +#if defined(LPTIM1) +/** + * @brief Get LPTIMx clock source + * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_GetLPTIMClockSource + * @param LPTIMx This parameter can be one of the following values: + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE + */ +__STATIC_INLINE uint32_t LL_RCC_GetLPTIMClockSource(uint32_t LPTIMx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)); +} +#endif /* LPTIM1 */ + +#if defined(SAI1) +/** + * @brief Get SAIx clock source + * @rmtoll DCKCFGR SAI1SEL LL_RCC_GetSAIClockSource\n + * DCKCFGR SAI2SEL LL_RCC_GetSAIClockSource\n + * DCKCFGR SAI1ASRC LL_RCC_GetSAIClockSource\n + * DCKCFGR SAI1BSRC LL_RCC_GetSAIClockSource + * @param SAIx This parameter can be one of the following values: + * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) + * + * (*) value not defined in all devices. + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetSAIClockSource(uint32_t SAIx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, SAIx) >> 16U | SAIx); +} +#endif /* SAI1 */ + +#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) +/** + * @brief Get SDIOx clock source + * @rmtoll DCKCFGR SDIOSEL LL_RCC_GetSDIOClockSource\n + * DCKCFGR2 SDIOSEL LL_RCC_GetSDIOClockSource + * @param SDIOx This parameter can be one of the following values: + * @arg @ref LL_RCC_SDIO_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK + * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK + */ +__STATIC_INLINE uint32_t LL_RCC_GetSDIOClockSource(uint32_t SDIOx) +{ +#if defined(RCC_DCKCFGR_SDIOSEL) + return (uint32_t)(READ_BIT(RCC->DCKCFGR, SDIOx)); +#else + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SDIOx)); +#endif /* RCC_DCKCFGR_SDIOSEL */ +} +#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) +/** + * @brief Get 48Mhz domain clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetCK48MClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_GetCK48MClockSource + * @param CK48Mx This parameter can be one of the following values: + * @arg @ref LL_RCC_CK48M_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetCK48MClockSource(uint32_t CK48Mx) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + return (uint32_t)(READ_BIT(RCC->DCKCFGR, CK48Mx)); +#else + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CK48Mx)); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} + +#if defined(RNG) +/** + * @brief Get RNGx clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetRNGClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_GetRNGClockSource + * @param RNGx This parameter can be one of the following values: + * @arg @ref LL_RCC_RNG_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetRNGClockSource(uint32_t RNGx) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RNGx)); +#else + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RNGx)); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} +#endif /* RNG */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +/** + * @brief Get USBx clock source + * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetUSBClockSource\n + * DCKCFGR2 CK48MSEL LL_RCC_GetUSBClockSource + * @param USBx This parameter can be one of the following values: + * @arg @ref LL_RCC_USB_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_USB_CLKSOURCE_PLL + * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) + * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetUSBClockSource(uint32_t USBx) +{ +#if defined(RCC_DCKCFGR_CK48MSEL) + return (uint32_t)(READ_BIT(RCC->DCKCFGR, USBx)); +#else + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, USBx)); +#endif /* RCC_DCKCFGR_CK48MSEL */ +} +#endif /* USB_OTG_FS || USB_OTG_HS */ +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + +#if defined(CEC) +/** + * @brief Get CEC Clock Source + * @rmtoll DCKCFGR2 CECSEL LL_RCC_GetCECClockSource + * @param CECx This parameter can be one of the following values: + * @arg @ref LL_RCC_CEC_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 + * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE + */ +__STATIC_INLINE uint32_t LL_RCC_GetCECClockSource(uint32_t CECx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CECx)); +} +#endif /* CEC */ + +/** + * @brief Get I2S Clock Source + * @rmtoll CFGR I2SSRC LL_RCC_GetI2SClockSource\n + * DCKCFGR I2SSRC LL_RCC_GetI2SClockSource\n + * DCKCFGR I2S1SRC LL_RCC_GetI2SClockSource\n + * DCKCFGR I2S2SRC LL_RCC_GetI2SClockSource + * @param I2Sx This parameter can be one of the following values: + * @arg @ref LL_RCC_I2S1_CLKSOURCE + * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) + * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetI2SClockSource(uint32_t I2Sx) +{ +#if defined(RCC_CFGR_I2SSRC) + return (uint32_t)(READ_BIT(RCC->CFGR, I2Sx)); +#else + return (uint32_t)(READ_BIT(RCC->DCKCFGR, I2Sx) >> 16U | I2Sx); +#endif /* RCC_CFGR_I2SSRC */ +} + +#if defined(DFSDM1_Channel0) +/** + * @brief Get DFSDM Audio Clock Source + * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_GetDFSDMAudioClockSource\n + * DCKCFGR CKDFSDM2ASEL LL_RCC_GetDFSDMAudioClockSource + * @param DFSDMx This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetDFSDMAudioClockSource(uint32_t DFSDMx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx) << 16U | DFSDMx); +} + +/** + * @brief Get DFSDM Audio Clock Source + * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_GetDFSDMClockSource + * @param DFSDMx This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetDFSDMClockSource(uint32_t DFSDMx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx)); +} +#endif /* DFSDM1_Channel0 */ + +#if defined(SPDIFRX) +/** + * @brief Get SPDIFRX clock source + * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_GetSPDIFRXClockSource + * @param SPDIFRXx This parameter can be one of the following values: + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_GetSPDIFRXClockSource(uint32_t SPDIFRXx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SPDIFRXx)); +} +#endif /* SPDIFRX */ + +#if defined(DSI) +/** + * @brief Get DSI Clock Source + * @rmtoll DCKCFGR DSISEL LL_RCC_GetDSIClockSource + * @param DSIx This parameter can be one of the following values: + * @arg @ref LL_RCC_DSI_CLKSOURCE + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY + * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL + */ +__STATIC_INLINE uint32_t LL_RCC_GetDSIClockSource(uint32_t DSIx) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, DSIx)); +} +#endif /* DSI */ + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_RTC RTC + * @{ + */ + +/** + * @brief Set RTC Clock Source + * @note Once the RTC clock source has been selected, it cannot be changed anymore unless + * the Backup domain is reset, or unless a failure is detected on LSE (LSECSSD is + * set). The BDRST bit can be used to reset them. + * @rmtoll BDCR RTCSEL LL_RCC_SetRTCClockSource + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE + * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE + * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI + * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetRTCClockSource(uint32_t Source) +{ + MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, Source); +} + +/** + * @brief Get RTC Clock Source + * @rmtoll BDCR RTCSEL LL_RCC_GetRTCClockSource + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE + * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE + * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI + * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE + */ +__STATIC_INLINE uint32_t LL_RCC_GetRTCClockSource(void) +{ + return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)); +} + +/** + * @brief Enable RTC + * @rmtoll BDCR RTCEN LL_RCC_EnableRTC + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableRTC(void) +{ + SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN); +} + +/** + * @brief Disable RTC + * @rmtoll BDCR RTCEN LL_RCC_DisableRTC + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableRTC(void) +{ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN); +} + +/** + * @brief Check if RTC has been enabled or not + * @rmtoll BDCR RTCEN LL_RCC_IsEnabledRTC + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledRTC(void) +{ + return (READ_BIT(RCC->BDCR, RCC_BDCR_RTCEN) == (RCC_BDCR_RTCEN)); +} + +/** + * @brief Force the Backup domain reset + * @rmtoll BDCR BDRST LL_RCC_ForceBackupDomainReset + * @retval None + */ +__STATIC_INLINE void LL_RCC_ForceBackupDomainReset(void) +{ + SET_BIT(RCC->BDCR, RCC_BDCR_BDRST); +} + +/** + * @brief Release the Backup domain reset + * @rmtoll BDCR BDRST LL_RCC_ReleaseBackupDomainReset + * @retval None + */ +__STATIC_INLINE void LL_RCC_ReleaseBackupDomainReset(void) +{ + CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST); +} + +/** + * @brief Set HSE Prescalers for RTC Clock + * @rmtoll CFGR RTCPRE LL_RCC_SetRTC_HSEPrescaler + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_RTC_NOCLOCK + * @arg @ref LL_RCC_RTC_HSE_DIV_2 + * @arg @ref LL_RCC_RTC_HSE_DIV_3 + * @arg @ref LL_RCC_RTC_HSE_DIV_4 + * @arg @ref LL_RCC_RTC_HSE_DIV_5 + * @arg @ref LL_RCC_RTC_HSE_DIV_6 + * @arg @ref LL_RCC_RTC_HSE_DIV_7 + * @arg @ref LL_RCC_RTC_HSE_DIV_8 + * @arg @ref LL_RCC_RTC_HSE_DIV_9 + * @arg @ref LL_RCC_RTC_HSE_DIV_10 + * @arg @ref LL_RCC_RTC_HSE_DIV_11 + * @arg @ref LL_RCC_RTC_HSE_DIV_12 + * @arg @ref LL_RCC_RTC_HSE_DIV_13 + * @arg @ref LL_RCC_RTC_HSE_DIV_14 + * @arg @ref LL_RCC_RTC_HSE_DIV_15 + * @arg @ref LL_RCC_RTC_HSE_DIV_16 + * @arg @ref LL_RCC_RTC_HSE_DIV_17 + * @arg @ref LL_RCC_RTC_HSE_DIV_18 + * @arg @ref LL_RCC_RTC_HSE_DIV_19 + * @arg @ref LL_RCC_RTC_HSE_DIV_20 + * @arg @ref LL_RCC_RTC_HSE_DIV_21 + * @arg @ref LL_RCC_RTC_HSE_DIV_22 + * @arg @ref LL_RCC_RTC_HSE_DIV_23 + * @arg @ref LL_RCC_RTC_HSE_DIV_24 + * @arg @ref LL_RCC_RTC_HSE_DIV_25 + * @arg @ref LL_RCC_RTC_HSE_DIV_26 + * @arg @ref LL_RCC_RTC_HSE_DIV_27 + * @arg @ref LL_RCC_RTC_HSE_DIV_28 + * @arg @ref LL_RCC_RTC_HSE_DIV_29 + * @arg @ref LL_RCC_RTC_HSE_DIV_30 + * @arg @ref LL_RCC_RTC_HSE_DIV_31 + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetRTC_HSEPrescaler(uint32_t Prescaler) +{ + MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, Prescaler); +} + +/** + * @brief Get HSE Prescalers for RTC Clock + * @rmtoll CFGR RTCPRE LL_RCC_GetRTC_HSEPrescaler + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_RTC_NOCLOCK + * @arg @ref LL_RCC_RTC_HSE_DIV_2 + * @arg @ref LL_RCC_RTC_HSE_DIV_3 + * @arg @ref LL_RCC_RTC_HSE_DIV_4 + * @arg @ref LL_RCC_RTC_HSE_DIV_5 + * @arg @ref LL_RCC_RTC_HSE_DIV_6 + * @arg @ref LL_RCC_RTC_HSE_DIV_7 + * @arg @ref LL_RCC_RTC_HSE_DIV_8 + * @arg @ref LL_RCC_RTC_HSE_DIV_9 + * @arg @ref LL_RCC_RTC_HSE_DIV_10 + * @arg @ref LL_RCC_RTC_HSE_DIV_11 + * @arg @ref LL_RCC_RTC_HSE_DIV_12 + * @arg @ref LL_RCC_RTC_HSE_DIV_13 + * @arg @ref LL_RCC_RTC_HSE_DIV_14 + * @arg @ref LL_RCC_RTC_HSE_DIV_15 + * @arg @ref LL_RCC_RTC_HSE_DIV_16 + * @arg @ref LL_RCC_RTC_HSE_DIV_17 + * @arg @ref LL_RCC_RTC_HSE_DIV_18 + * @arg @ref LL_RCC_RTC_HSE_DIV_19 + * @arg @ref LL_RCC_RTC_HSE_DIV_20 + * @arg @ref LL_RCC_RTC_HSE_DIV_21 + * @arg @ref LL_RCC_RTC_HSE_DIV_22 + * @arg @ref LL_RCC_RTC_HSE_DIV_23 + * @arg @ref LL_RCC_RTC_HSE_DIV_24 + * @arg @ref LL_RCC_RTC_HSE_DIV_25 + * @arg @ref LL_RCC_RTC_HSE_DIV_26 + * @arg @ref LL_RCC_RTC_HSE_DIV_27 + * @arg @ref LL_RCC_RTC_HSE_DIV_28 + * @arg @ref LL_RCC_RTC_HSE_DIV_29 + * @arg @ref LL_RCC_RTC_HSE_DIV_30 + * @arg @ref LL_RCC_RTC_HSE_DIV_31 + */ +__STATIC_INLINE uint32_t LL_RCC_GetRTC_HSEPrescaler(void) +{ + return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE)); +} + +/** + * @} + */ + +#if defined(RCC_DCKCFGR_TIMPRE) +/** @defgroup RCC_LL_EF_TIM_CLOCK_PRESCALER TIM + * @{ + */ + +/** + * @brief Set Timers Clock Prescalers + * @rmtoll DCKCFGR TIMPRE LL_RCC_SetTIMPrescaler + * @param Prescaler This parameter can be one of the following values: + * @arg @ref LL_RCC_TIM_PRESCALER_TWICE + * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES + * @retval None + */ +__STATIC_INLINE void LL_RCC_SetTIMPrescaler(uint32_t Prescaler) +{ + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE, Prescaler); +} + +/** + * @brief Get Timers Clock Prescalers + * @rmtoll DCKCFGR TIMPRE LL_RCC_GetTIMPrescaler + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_TIM_PRESCALER_TWICE + * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES + */ +__STATIC_INLINE uint32_t LL_RCC_GetTIMPrescaler(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE)); +} + +/** + * @} + */ +#endif /* RCC_DCKCFGR_TIMPRE */ + +/** @defgroup RCC_LL_EF_PLL PLL + * @{ + */ + +/** + * @brief Enable PLL + * @rmtoll CR PLLON LL_RCC_PLL_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_Enable(void) +{ + SET_BIT(RCC->CR, RCC_CR_PLLON); +} + +/** + * @brief Disable PLL + * @note Cannot be disabled if the PLL clock is used as the system clock + * @rmtoll CR PLLON LL_RCC_PLL_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_Disable(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_PLLON); +} + +/** + * @brief Check if PLL Ready + * @rmtoll CR PLLRDY LL_RCC_PLL_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_IsReady(void) +{ + return (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == (RCC_CR_PLLRDY)); +} + +/** + * @brief Configure PLL used for SYSCLK Domain + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLP can be written only when PLL is disabled + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SYS\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SYS\n + * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SYS\n + * PLLCFGR PLLP LL_RCC_PLL_ConfigDomain_SYS + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLP_R This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLP_DIV_2 + * @arg @ref LL_RCC_PLLP_DIV_4 + * @arg @ref LL_RCC_PLLP_DIV_6 + * @arg @ref LL_RCC_PLLP_DIV_8 + * @arg @ref LL_RCC_PLLR_DIV_2 (*) + * @arg @ref LL_RCC_PLLR_DIV_3 (*) + * @arg @ref LL_RCC_PLLR_DIV_4 (*) + * @arg @ref LL_RCC_PLLR_DIV_5 (*) + * @arg @ref LL_RCC_PLLR_DIV_6 (*) + * @arg @ref LL_RCC_PLLR_DIV_7 (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP_R) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos); + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLP, PLLP_R); +#if defined(RCC_PLLR_SYSCLK_SUPPORT) + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLR, PLLP_R); +#endif /* RCC_PLLR_SYSCLK_SUPPORT */ +} + +/** + * @brief Configure PLL used for 48Mhz domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLQ can be written only when PLL is disabled + * @note This can be selected for USB, RNG, SDIO + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_48M\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_48M\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_48M\n + * PLLCFGR PLLQ LL_RCC_PLL_ConfigDomain_48M + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLQ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLQ_DIV_2 + * @arg @ref LL_RCC_PLLQ_DIV_3 + * @arg @ref LL_RCC_PLLQ_DIV_4 + * @arg @ref LL_RCC_PLLQ_DIV_5 + * @arg @ref LL_RCC_PLLQ_DIV_6 + * @arg @ref LL_RCC_PLLQ_DIV_7 + * @arg @ref LL_RCC_PLLQ_DIV_8 + * @arg @ref LL_RCC_PLLQ_DIV_9 + * @arg @ref LL_RCC_PLLQ_DIV_10 + * @arg @ref LL_RCC_PLLQ_DIV_11 + * @arg @ref LL_RCC_PLLQ_DIV_12 + * @arg @ref LL_RCC_PLLQ_DIV_13 + * @arg @ref LL_RCC_PLLQ_DIV_14 + * @arg @ref LL_RCC_PLLQ_DIV_15 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLQ, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLQ); +} + +#if defined(DSI) +/** + * @brief Configure PLL used for DSI clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI are disabled + * @note PLLN/PLLR can be written only when PLL is disabled + * @note This can be selected for DSI + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_DSI\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_DSI\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_DSI\n + * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_DSI + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_DSI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); +} +#endif /* DSI */ + +#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) +/** + * @brief Configure PLL used for I2S clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI are disabled + * @note PLLN/PLLR can be written only when PLL is disabled + * @note This can be selected for I2S + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_I2S\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_I2S\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_I2S\n + * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_I2S + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); +} +#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ + +#if defined(SPDIFRX) +/** + * @brief Configure PLL used for SPDIFRX clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI are disabled + * @note PLLN/PLLR can be written only when PLL is disabled + * @note This can be selected for SPDIFRX + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SPDIFRX\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SPDIFRX\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SPDIFRX\n + * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SPDIFRX + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); +} +#endif /* SPDIFRX */ + +#if defined(RCC_PLLCFGR_PLLR) +#if defined(SAI1) +/** + * @brief Configure PLL used for SAI clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI are disabled + * @note PLLN/PLLR can be written only when PLL is disabled + * @note This can be selected for SAI + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SAI\n + * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SAI\n + * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SAI\n + * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SAI\n + * DCKCFGR PLLDIVR LL_RCC_PLL_ConfigDomain_SAI + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + * @param PLLDIVR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) + * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) + * + * (*) value not defined in all devices. + * @retval None + */ +#if defined(RCC_DCKCFGR_PLLDIVR) +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) +#else +__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) +#endif /* RCC_DCKCFGR_PLLDIVR */ +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, + Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); +#if defined(RCC_DCKCFGR_PLLDIVR) + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, PLLDIVR); +#endif /* RCC_DCKCFGR_PLLDIVR */ +} +#endif /* SAI1 */ +#endif /* RCC_PLLCFGR_PLLR */ + +/** + * @brief Configure PLL clock source + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_SetMainSource + * @param PLLSource This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_SetMainSource(uint32_t PLLSource) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, PLLSource); +} + +/** + * @brief Get the oscillator used as PLL clock source. + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_GetMainSource + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetMainSource(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); +} + +/** + * @brief Get Main PLL multiplication factor for VCO + * @rmtoll PLLCFGR PLLN LL_RCC_PLL_GetN + * @retval Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetN(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); +} + +/** + * @brief Get Main PLL division factor for PLLP + * @rmtoll PLLCFGR PLLP LL_RCC_PLL_GetP + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLP_DIV_2 + * @arg @ref LL_RCC_PLLP_DIV_4 + * @arg @ref LL_RCC_PLLP_DIV_6 + * @arg @ref LL_RCC_PLLP_DIV_8 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetP(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLP)); +} + +/** + * @brief Get Main PLL division factor for PLLQ + * @note used for PLL48MCLK selected for USB, RNG, SDIO (48 MHz clock) + * @rmtoll PLLCFGR PLLQ LL_RCC_PLL_GetQ + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLQ_DIV_2 + * @arg @ref LL_RCC_PLLQ_DIV_3 + * @arg @ref LL_RCC_PLLQ_DIV_4 + * @arg @ref LL_RCC_PLLQ_DIV_5 + * @arg @ref LL_RCC_PLLQ_DIV_6 + * @arg @ref LL_RCC_PLLQ_DIV_7 + * @arg @ref LL_RCC_PLLQ_DIV_8 + * @arg @ref LL_RCC_PLLQ_DIV_9 + * @arg @ref LL_RCC_PLLQ_DIV_10 + * @arg @ref LL_RCC_PLLQ_DIV_11 + * @arg @ref LL_RCC_PLLQ_DIV_12 + * @arg @ref LL_RCC_PLLQ_DIV_13 + * @arg @ref LL_RCC_PLLQ_DIV_14 + * @arg @ref LL_RCC_PLLQ_DIV_15 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetQ(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ)); +} + +#if defined(RCC_PLLCFGR_PLLR) +/** + * @brief Get Main PLL division factor for PLLR + * @note used for PLLCLK (system clock) + * @rmtoll PLLCFGR PLLR LL_RCC_PLL_GetR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLR_DIV_2 + * @arg @ref LL_RCC_PLLR_DIV_3 + * @arg @ref LL_RCC_PLLR_DIV_4 + * @arg @ref LL_RCC_PLLR_DIV_5 + * @arg @ref LL_RCC_PLLR_DIV_6 + * @arg @ref LL_RCC_PLLR_DIV_7 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetR(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR)); +} +#endif /* RCC_PLLCFGR_PLLR */ + +#if defined(RCC_DCKCFGR_PLLDIVR) +/** + * @brief Get Main PLL division factor for PLLDIVR + * @note used for PLLSAICLK (SAI1 and SAI2 clock) + * @rmtoll DCKCFGR PLLDIVR LL_RCC_PLL_GetDIVR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLDIVR_DIV_1 + * @arg @ref LL_RCC_PLLDIVR_DIV_2 + * @arg @ref LL_RCC_PLLDIVR_DIV_3 + * @arg @ref LL_RCC_PLLDIVR_DIV_4 + * @arg @ref LL_RCC_PLLDIVR_DIV_5 + * @arg @ref LL_RCC_PLLDIVR_DIV_6 + * @arg @ref LL_RCC_PLLDIVR_DIV_7 + * @arg @ref LL_RCC_PLLDIVR_DIV_8 + * @arg @ref LL_RCC_PLLDIVR_DIV_9 + * @arg @ref LL_RCC_PLLDIVR_DIV_10 + * @arg @ref LL_RCC_PLLDIVR_DIV_11 + * @arg @ref LL_RCC_PLLDIVR_DIV_12 + * @arg @ref LL_RCC_PLLDIVR_DIV_13 + * @arg @ref LL_RCC_PLLDIVR_DIV_14 + * @arg @ref LL_RCC_PLLDIVR_DIV_15 + * @arg @ref LL_RCC_PLLDIVR_DIV_16 + * @arg @ref LL_RCC_PLLDIVR_DIV_17 + * @arg @ref LL_RCC_PLLDIVR_DIV_18 + * @arg @ref LL_RCC_PLLDIVR_DIV_19 + * @arg @ref LL_RCC_PLLDIVR_DIV_20 + * @arg @ref LL_RCC_PLLDIVR_DIV_21 + * @arg @ref LL_RCC_PLLDIVR_DIV_22 + * @arg @ref LL_RCC_PLLDIVR_DIV_23 + * @arg @ref LL_RCC_PLLDIVR_DIV_24 + * @arg @ref LL_RCC_PLLDIVR_DIV_25 + * @arg @ref LL_RCC_PLLDIVR_DIV_26 + * @arg @ref LL_RCC_PLLDIVR_DIV_27 + * @arg @ref LL_RCC_PLLDIVR_DIV_28 + * @arg @ref LL_RCC_PLLDIVR_DIV_29 + * @arg @ref LL_RCC_PLLDIVR_DIV_30 + * @arg @ref LL_RCC_PLLDIVR_DIV_31 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetDIVR(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR)); +} +#endif /* RCC_DCKCFGR_PLLDIVR */ + +/** + * @brief Get Division factor for the main PLL and other PLL + * @rmtoll PLLCFGR PLLM LL_RCC_PLL_GetDivider + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLM_DIV_2 + * @arg @ref LL_RCC_PLLM_DIV_3 + * @arg @ref LL_RCC_PLLM_DIV_4 + * @arg @ref LL_RCC_PLLM_DIV_5 + * @arg @ref LL_RCC_PLLM_DIV_6 + * @arg @ref LL_RCC_PLLM_DIV_7 + * @arg @ref LL_RCC_PLLM_DIV_8 + * @arg @ref LL_RCC_PLLM_DIV_9 + * @arg @ref LL_RCC_PLLM_DIV_10 + * @arg @ref LL_RCC_PLLM_DIV_11 + * @arg @ref LL_RCC_PLLM_DIV_12 + * @arg @ref LL_RCC_PLLM_DIV_13 + * @arg @ref LL_RCC_PLLM_DIV_14 + * @arg @ref LL_RCC_PLLM_DIV_15 + * @arg @ref LL_RCC_PLLM_DIV_16 + * @arg @ref LL_RCC_PLLM_DIV_17 + * @arg @ref LL_RCC_PLLM_DIV_18 + * @arg @ref LL_RCC_PLLM_DIV_19 + * @arg @ref LL_RCC_PLLM_DIV_20 + * @arg @ref LL_RCC_PLLM_DIV_21 + * @arg @ref LL_RCC_PLLM_DIV_22 + * @arg @ref LL_RCC_PLLM_DIV_23 + * @arg @ref LL_RCC_PLLM_DIV_24 + * @arg @ref LL_RCC_PLLM_DIV_25 + * @arg @ref LL_RCC_PLLM_DIV_26 + * @arg @ref LL_RCC_PLLM_DIV_27 + * @arg @ref LL_RCC_PLLM_DIV_28 + * @arg @ref LL_RCC_PLLM_DIV_29 + * @arg @ref LL_RCC_PLLM_DIV_30 + * @arg @ref LL_RCC_PLLM_DIV_31 + * @arg @ref LL_RCC_PLLM_DIV_32 + * @arg @ref LL_RCC_PLLM_DIV_33 + * @arg @ref LL_RCC_PLLM_DIV_34 + * @arg @ref LL_RCC_PLLM_DIV_35 + * @arg @ref LL_RCC_PLLM_DIV_36 + * @arg @ref LL_RCC_PLLM_DIV_37 + * @arg @ref LL_RCC_PLLM_DIV_38 + * @arg @ref LL_RCC_PLLM_DIV_39 + * @arg @ref LL_RCC_PLLM_DIV_40 + * @arg @ref LL_RCC_PLLM_DIV_41 + * @arg @ref LL_RCC_PLLM_DIV_42 + * @arg @ref LL_RCC_PLLM_DIV_43 + * @arg @ref LL_RCC_PLLM_DIV_44 + * @arg @ref LL_RCC_PLLM_DIV_45 + * @arg @ref LL_RCC_PLLM_DIV_46 + * @arg @ref LL_RCC_PLLM_DIV_47 + * @arg @ref LL_RCC_PLLM_DIV_48 + * @arg @ref LL_RCC_PLLM_DIV_49 + * @arg @ref LL_RCC_PLLM_DIV_50 + * @arg @ref LL_RCC_PLLM_DIV_51 + * @arg @ref LL_RCC_PLLM_DIV_52 + * @arg @ref LL_RCC_PLLM_DIV_53 + * @arg @ref LL_RCC_PLLM_DIV_54 + * @arg @ref LL_RCC_PLLM_DIV_55 + * @arg @ref LL_RCC_PLLM_DIV_56 + * @arg @ref LL_RCC_PLLM_DIV_57 + * @arg @ref LL_RCC_PLLM_DIV_58 + * @arg @ref LL_RCC_PLLM_DIV_59 + * @arg @ref LL_RCC_PLLM_DIV_60 + * @arg @ref LL_RCC_PLLM_DIV_61 + * @arg @ref LL_RCC_PLLM_DIV_62 + * @arg @ref LL_RCC_PLLM_DIV_63 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetDivider(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); +} + +/** + * @brief Configure Spread Spectrum used for PLL + * @note These bits must be written before enabling PLL + * @rmtoll SSCGR MODPER LL_RCC_PLL_ConfigSpreadSpectrum\n + * SSCGR INCSTEP LL_RCC_PLL_ConfigSpreadSpectrum\n + * SSCGR SPREADSEL LL_RCC_PLL_ConfigSpreadSpectrum + * @param Mod Between Min_Data=0 and Max_Data=8191 + * @param Inc Between Min_Data=0 and Max_Data=32767 + * @param Sel This parameter can be one of the following values: + * @arg @ref LL_RCC_SPREAD_SELECT_CENTER + * @arg @ref LL_RCC_SPREAD_SELECT_DOWN + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_ConfigSpreadSpectrum(uint32_t Mod, uint32_t Inc, uint32_t Sel) +{ + MODIFY_REG(RCC->SSCGR, RCC_SSCGR_MODPER | RCC_SSCGR_INCSTEP | RCC_SSCGR_SPREADSEL, Mod | (Inc << RCC_SSCGR_INCSTEP_Pos) | Sel); +} + +/** + * @brief Get Spread Spectrum Modulation Period for PLL + * @rmtoll SSCGR MODPER LL_RCC_PLL_GetPeriodModulation + * @retval Between Min_Data=0 and Max_Data=8191 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetPeriodModulation(void) +{ + return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_MODPER)); +} + +/** + * @brief Get Spread Spectrum Incrementation Step for PLL + * @note Must be written before enabling PLL + * @rmtoll SSCGR INCSTEP LL_RCC_PLL_GetStepIncrementation + * @retval Between Min_Data=0 and Max_Data=32767 + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetStepIncrementation(void) +{ + return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_INCSTEP) >> RCC_SSCGR_INCSTEP_Pos); +} + +/** + * @brief Get Spread Spectrum Selection for PLL + * @note Must be written before enabling PLL + * @rmtoll SSCGR SPREADSEL LL_RCC_PLL_GetSpreadSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_SPREAD_SELECT_CENTER + * @arg @ref LL_RCC_SPREAD_SELECT_DOWN + */ +__STATIC_INLINE uint32_t LL_RCC_PLL_GetSpreadSelection(void) +{ + return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_SPREADSEL)); +} + +/** + * @brief Enable Spread Spectrum for PLL. + * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Enable(void) +{ + SET_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); +} + +/** + * @brief Disable Spread Spectrum for PLL. + * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Disable(void) +{ + CLEAR_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); +} + +/** + * @} + */ + +#if defined(RCC_PLLI2S_SUPPORT) +/** @defgroup RCC_LL_EF_PLLI2S PLLI2S + * @{ + */ + +/** + * @brief Enable PLLI2S + * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_Enable(void) +{ + SET_BIT(RCC->CR, RCC_CR_PLLI2SON); +} + +/** + * @brief Disable PLLI2S + * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_Disable(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); +} + +/** + * @brief Check if PLLI2S Ready + * @rmtoll CR PLLI2SRDY LL_RCC_PLLI2S_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_IsReady(void) +{ + return (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) == (RCC_CR_PLLI2SRDY)); +} + +#if (defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR)) +/** + * @brief Configure PLLI2S used for SAI domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLQ/PLLR can be written only when PLLI2S is disabled + * @note This can be selected for SAI + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_SAI\n + * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_SAI\n + * DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_ConfigDomain_SAI\n + * DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_ConfigDomain_SAI + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) + * + * (*) value not defined in all devices. + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param PLLN Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLQ_R This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) + * + * (*) value not defined in all devices. + * @param PLLDIVQ_R This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ_R, uint32_t PLLDIVQ_R) +{ + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); + MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos); +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ, PLLQ_R); + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, PLLDIVQ_R); +#else + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR, PLLQ_R); + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, PLLDIVQ_R); +#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ +} +#endif /* RCC_DCKCFGR_PLLI2SDIVQ && RCC_DCKCFGR_PLLI2SDIVR */ + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +/** + * @brief Configure PLLI2S used for 48Mhz domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLQ can be written only when PLLI2S is disabled + * @note This can be selected for RNG, USB, SDIO + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_48M\n + * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_48M\n + * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_48M\n + * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_48M\n + * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_48M\n + * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_48M + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) + * + * (*) value not defined in all devices. + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLQ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SQ_DIV_2 + * @arg @ref LL_RCC_PLLI2SQ_DIV_3 + * @arg @ref LL_RCC_PLLI2SQ_DIV_4 + * @arg @ref LL_RCC_PLLI2SQ_DIV_5 + * @arg @ref LL_RCC_PLLI2SQ_DIV_6 + * @arg @ref LL_RCC_PLLI2SQ_DIV_7 + * @arg @ref LL_RCC_PLLI2SQ_DIV_8 + * @arg @ref LL_RCC_PLLI2SQ_DIV_9 + * @arg @ref LL_RCC_PLLI2SQ_DIV_10 + * @arg @ref LL_RCC_PLLI2SQ_DIV_11 + * @arg @ref LL_RCC_PLLI2SQ_DIV_12 + * @arg @ref LL_RCC_PLLI2SQ_DIV_13 + * @arg @ref LL_RCC_PLLI2SQ_DIV_14 + * @arg @ref LL_RCC_PLLI2SQ_DIV_15 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) +{ + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); + MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SQ, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLQ); +} +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ + +#if defined(SPDIFRX) +/** + * @brief Configure PLLI2S used for SPDIFRX domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLP can be written only when PLLI2S is disabled + * @note This can be selected for SPDIFRX + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n + * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n + * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n + * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n + * PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_ConfigDomain_SPDIFRX + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLP This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SP_DIV_2 + * @arg @ref LL_RCC_PLLI2SP_DIV_4 + * @arg @ref LL_RCC_PLLI2SP_DIV_6 + * @arg @ref LL_RCC_PLLI2SP_DIV_8 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SP, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLP); +} +#endif /* SPDIFRX */ + +/** + * @brief Configure PLLI2S used for I2S1 domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLR can be written only when PLLI2S is disabled + * @note This can be selected for I2S + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n + * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_I2S\n + * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n + * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_I2S\n + * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_I2S\n + * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_I2S + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) + * + * (*) value not defined in all devices. + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + * @param PLLN Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLI2SR_DIV_2 + * @arg @ref LL_RCC_PLLI2SR_DIV_3 + * @arg @ref LL_RCC_PLLI2SR_DIV_4 + * @arg @ref LL_RCC_PLLI2SR_DIV_5 + * @arg @ref LL_RCC_PLLI2SR_DIV_6 + * @arg @ref LL_RCC_PLLI2SR_DIV_7 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) +{ + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); + MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ + MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SR, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLR); +} + +/** + * @brief Get I2SPLL multiplication factor for VCO + * @rmtoll PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_GetN + * @retval Between 50/192(*) and 432 + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetN(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); +} + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) +/** + * @brief Get I2SPLL division factor for PLLI2SQ + * @rmtoll PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_GetQ + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SQ_DIV_2 + * @arg @ref LL_RCC_PLLI2SQ_DIV_3 + * @arg @ref LL_RCC_PLLI2SQ_DIV_4 + * @arg @ref LL_RCC_PLLI2SQ_DIV_5 + * @arg @ref LL_RCC_PLLI2SQ_DIV_6 + * @arg @ref LL_RCC_PLLI2SQ_DIV_7 + * @arg @ref LL_RCC_PLLI2SQ_DIV_8 + * @arg @ref LL_RCC_PLLI2SQ_DIV_9 + * @arg @ref LL_RCC_PLLI2SQ_DIV_10 + * @arg @ref LL_RCC_PLLI2SQ_DIV_11 + * @arg @ref LL_RCC_PLLI2SQ_DIV_12 + * @arg @ref LL_RCC_PLLI2SQ_DIV_13 + * @arg @ref LL_RCC_PLLI2SQ_DIV_14 + * @arg @ref LL_RCC_PLLI2SQ_DIV_15 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetQ(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ)); +} +#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ + +/** + * @brief Get I2SPLL division factor for PLLI2SR + * @note used for PLLI2SCLK (I2S clock) + * @rmtoll PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_GetR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SR_DIV_2 + * @arg @ref LL_RCC_PLLI2SR_DIV_3 + * @arg @ref LL_RCC_PLLI2SR_DIV_4 + * @arg @ref LL_RCC_PLLI2SR_DIV_5 + * @arg @ref LL_RCC_PLLI2SR_DIV_6 + * @arg @ref LL_RCC_PLLI2SR_DIV_7 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetR(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR)); +} + +#if defined(RCC_PLLI2SCFGR_PLLI2SP) +/** + * @brief Get I2SPLL division factor for PLLI2SP + * @note used for PLLSPDIFRXCLK (SPDIFRX clock) + * @rmtoll PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_GetP + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SP_DIV_2 + * @arg @ref LL_RCC_PLLI2SP_DIV_4 + * @arg @ref LL_RCC_PLLI2SP_DIV_6 + * @arg @ref LL_RCC_PLLI2SP_DIV_8 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetP(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SP)); +} +#endif /* RCC_PLLI2SCFGR_PLLI2SP */ + +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) +/** + * @brief Get I2SPLL division factor for PLLI2SDIVQ + * @note used PLLSAICLK selected (SAI clock) + * @rmtoll DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_GetDIVQ + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 + * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVQ(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ)); +} +#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ + +#if defined(RCC_DCKCFGR_PLLI2SDIVR) +/** + * @brief Get I2SPLL division factor for PLLI2SDIVR + * @note used PLLSAICLK selected (SAI clock) + * @rmtoll DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_GetDIVR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 + * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVR(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR)); +} +#endif /* RCC_DCKCFGR_PLLI2SDIVR */ + +/** + * @brief Get division factor for PLLI2S input clock + * @rmtoll PLLCFGR PLLM LL_RCC_PLLI2S_GetDivider\n + * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_GetDivider + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLI2SM_DIV_2 + * @arg @ref LL_RCC_PLLI2SM_DIV_3 + * @arg @ref LL_RCC_PLLI2SM_DIV_4 + * @arg @ref LL_RCC_PLLI2SM_DIV_5 + * @arg @ref LL_RCC_PLLI2SM_DIV_6 + * @arg @ref LL_RCC_PLLI2SM_DIV_7 + * @arg @ref LL_RCC_PLLI2SM_DIV_8 + * @arg @ref LL_RCC_PLLI2SM_DIV_9 + * @arg @ref LL_RCC_PLLI2SM_DIV_10 + * @arg @ref LL_RCC_PLLI2SM_DIV_11 + * @arg @ref LL_RCC_PLLI2SM_DIV_12 + * @arg @ref LL_RCC_PLLI2SM_DIV_13 + * @arg @ref LL_RCC_PLLI2SM_DIV_14 + * @arg @ref LL_RCC_PLLI2SM_DIV_15 + * @arg @ref LL_RCC_PLLI2SM_DIV_16 + * @arg @ref LL_RCC_PLLI2SM_DIV_17 + * @arg @ref LL_RCC_PLLI2SM_DIV_18 + * @arg @ref LL_RCC_PLLI2SM_DIV_19 + * @arg @ref LL_RCC_PLLI2SM_DIV_20 + * @arg @ref LL_RCC_PLLI2SM_DIV_21 + * @arg @ref LL_RCC_PLLI2SM_DIV_22 + * @arg @ref LL_RCC_PLLI2SM_DIV_23 + * @arg @ref LL_RCC_PLLI2SM_DIV_24 + * @arg @ref LL_RCC_PLLI2SM_DIV_25 + * @arg @ref LL_RCC_PLLI2SM_DIV_26 + * @arg @ref LL_RCC_PLLI2SM_DIV_27 + * @arg @ref LL_RCC_PLLI2SM_DIV_28 + * @arg @ref LL_RCC_PLLI2SM_DIV_29 + * @arg @ref LL_RCC_PLLI2SM_DIV_30 + * @arg @ref LL_RCC_PLLI2SM_DIV_31 + * @arg @ref LL_RCC_PLLI2SM_DIV_32 + * @arg @ref LL_RCC_PLLI2SM_DIV_33 + * @arg @ref LL_RCC_PLLI2SM_DIV_34 + * @arg @ref LL_RCC_PLLI2SM_DIV_35 + * @arg @ref LL_RCC_PLLI2SM_DIV_36 + * @arg @ref LL_RCC_PLLI2SM_DIV_37 + * @arg @ref LL_RCC_PLLI2SM_DIV_38 + * @arg @ref LL_RCC_PLLI2SM_DIV_39 + * @arg @ref LL_RCC_PLLI2SM_DIV_40 + * @arg @ref LL_RCC_PLLI2SM_DIV_41 + * @arg @ref LL_RCC_PLLI2SM_DIV_42 + * @arg @ref LL_RCC_PLLI2SM_DIV_43 + * @arg @ref LL_RCC_PLLI2SM_DIV_44 + * @arg @ref LL_RCC_PLLI2SM_DIV_45 + * @arg @ref LL_RCC_PLLI2SM_DIV_46 + * @arg @ref LL_RCC_PLLI2SM_DIV_47 + * @arg @ref LL_RCC_PLLI2SM_DIV_48 + * @arg @ref LL_RCC_PLLI2SM_DIV_49 + * @arg @ref LL_RCC_PLLI2SM_DIV_50 + * @arg @ref LL_RCC_PLLI2SM_DIV_51 + * @arg @ref LL_RCC_PLLI2SM_DIV_52 + * @arg @ref LL_RCC_PLLI2SM_DIV_53 + * @arg @ref LL_RCC_PLLI2SM_DIV_54 + * @arg @ref LL_RCC_PLLI2SM_DIV_55 + * @arg @ref LL_RCC_PLLI2SM_DIV_56 + * @arg @ref LL_RCC_PLLI2SM_DIV_57 + * @arg @ref LL_RCC_PLLI2SM_DIV_58 + * @arg @ref LL_RCC_PLLI2SM_DIV_59 + * @arg @ref LL_RCC_PLLI2SM_DIV_60 + * @arg @ref LL_RCC_PLLI2SM_DIV_61 + * @arg @ref LL_RCC_PLLI2SM_DIV_62 + * @arg @ref LL_RCC_PLLI2SM_DIV_63 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDivider(void) +{ +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM)); +#else + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ +} + +/** + * @brief Get the oscillator used as PLL clock source. + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_GetMainSource\n + * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_GetMainSource + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetMainSource(void) +{ +#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) + uint32_t pllsrc = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC); + uint32_t plli2sssrc0 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC); + uint32_t plli2sssrc1 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC) >> 15U; + return (uint32_t)(pllsrc | plli2sssrc0 | plli2sssrc1); +#else + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); +#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ +} + +/** + * @} + */ +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** @defgroup RCC_LL_EF_PLLSAI PLLSAI + * @{ + */ + +/** + * @brief Enable PLLSAI + * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Enable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLSAI_Enable(void) +{ + SET_BIT(RCC->CR, RCC_CR_PLLSAION); +} + +/** + * @brief Disable PLLSAI + * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Disable + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLSAI_Disable(void) +{ + CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); +} + +/** + * @brief Check if PLLSAI Ready + * @rmtoll CR PLLSAIRDY LL_RCC_PLLSAI_IsReady + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_IsReady(void) +{ + return (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) == (RCC_CR_PLLSAIRDY)); +} + +/** + * @brief Configure PLLSAI used for SAI domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLQ can be written only when PLLSAI is disabled + * @note This can be selected for SAI + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_SAI\n + * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_SAI\n + * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_SAI\n + * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_SAI\n + * PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_ConfigDomain_SAI\n + * DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_ConfigDomain_SAI + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param PLLN Between 49/50(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLQ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIQ_DIV_15 + * @param PLLDIVQ This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ, uint32_t PLLDIVQ) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); +#if defined(RCC_PLLSAICFGR_PLLSAIM) + MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLSAICFGR_PLLSAIM */ + MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIQ, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLQ); + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, PLLDIVQ); +} + +#if defined(RCC_PLLSAICFGR_PLLSAIP) +/** + * @brief Configure PLLSAI used for 48Mhz domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLP can be written only when PLLSAI is disabled + * @note This can be selected for USB, RNG, SDIO + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_48M\n + * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_48M\n + * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_48M\n + * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_48M\n + * PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_ConfigDomain_48M + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param PLLN Between 50 and 432 + * @param PLLP This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIP_DIV_2 + * @arg @ref LL_RCC_PLLSAIP_DIV_4 + * @arg @ref LL_RCC_PLLSAIP_DIV_6 + * @arg @ref LL_RCC_PLLSAIP_DIV_8 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); +#if defined(RCC_PLLSAICFGR_PLLSAIM) + MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); +#else + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); +#endif /* RCC_PLLSAICFGR_PLLSAIM */ + MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIP, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLP); +} +#endif /* RCC_PLLSAICFGR_PLLSAIP */ + +#if defined(LTDC) +/** + * @brief Configure PLLSAI used for LTDC domain clock + * @note PLL Source and PLLM Divider can be written only when PLL, + * PLLI2S and PLLSAI(*) are disabled + * @note PLLN/PLLR can be written only when PLLSAI is disabled + * @note This can be selected for LTDC + * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_LTDC\n + * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_LTDC\n + * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_LTDC\n + * PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_ConfigDomain_LTDC\n + * DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_ConfigDomain_LTDC + * @param Source This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSOURCE_HSI + * @arg @ref LL_RCC_PLLSOURCE_HSE + * @param PLLM This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + * @param PLLN Between 49/50(*) and 432 + * + * (*) value not defined in all devices. + * @param PLLR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIR_DIV_2 + * @arg @ref LL_RCC_PLLSAIR_DIV_3 + * @arg @ref LL_RCC_PLLSAIR_DIV_4 + * @arg @ref LL_RCC_PLLSAIR_DIV_5 + * @arg @ref LL_RCC_PLLSAIR_DIV_6 + * @arg @ref LL_RCC_PLLSAIR_DIV_7 + * @param PLLDIVR This parameter can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 + * @retval None + */ +__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_LTDC(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) +{ + MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM, Source | PLLM); + MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIR, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLR); + MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, PLLDIVR); +} +#endif /* LTDC */ + +/** + * @brief Get division factor for PLLSAI input clock + * @rmtoll PLLCFGR PLLM LL_RCC_PLLSAI_GetDivider\n + * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_GetDivider + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIM_DIV_2 + * @arg @ref LL_RCC_PLLSAIM_DIV_3 + * @arg @ref LL_RCC_PLLSAIM_DIV_4 + * @arg @ref LL_RCC_PLLSAIM_DIV_5 + * @arg @ref LL_RCC_PLLSAIM_DIV_6 + * @arg @ref LL_RCC_PLLSAIM_DIV_7 + * @arg @ref LL_RCC_PLLSAIM_DIV_8 + * @arg @ref LL_RCC_PLLSAIM_DIV_9 + * @arg @ref LL_RCC_PLLSAIM_DIV_10 + * @arg @ref LL_RCC_PLLSAIM_DIV_11 + * @arg @ref LL_RCC_PLLSAIM_DIV_12 + * @arg @ref LL_RCC_PLLSAIM_DIV_13 + * @arg @ref LL_RCC_PLLSAIM_DIV_14 + * @arg @ref LL_RCC_PLLSAIM_DIV_15 + * @arg @ref LL_RCC_PLLSAIM_DIV_16 + * @arg @ref LL_RCC_PLLSAIM_DIV_17 + * @arg @ref LL_RCC_PLLSAIM_DIV_18 + * @arg @ref LL_RCC_PLLSAIM_DIV_19 + * @arg @ref LL_RCC_PLLSAIM_DIV_20 + * @arg @ref LL_RCC_PLLSAIM_DIV_21 + * @arg @ref LL_RCC_PLLSAIM_DIV_22 + * @arg @ref LL_RCC_PLLSAIM_DIV_23 + * @arg @ref LL_RCC_PLLSAIM_DIV_24 + * @arg @ref LL_RCC_PLLSAIM_DIV_25 + * @arg @ref LL_RCC_PLLSAIM_DIV_26 + * @arg @ref LL_RCC_PLLSAIM_DIV_27 + * @arg @ref LL_RCC_PLLSAIM_DIV_28 + * @arg @ref LL_RCC_PLLSAIM_DIV_29 + * @arg @ref LL_RCC_PLLSAIM_DIV_30 + * @arg @ref LL_RCC_PLLSAIM_DIV_31 + * @arg @ref LL_RCC_PLLSAIM_DIV_32 + * @arg @ref LL_RCC_PLLSAIM_DIV_33 + * @arg @ref LL_RCC_PLLSAIM_DIV_34 + * @arg @ref LL_RCC_PLLSAIM_DIV_35 + * @arg @ref LL_RCC_PLLSAIM_DIV_36 + * @arg @ref LL_RCC_PLLSAIM_DIV_37 + * @arg @ref LL_RCC_PLLSAIM_DIV_38 + * @arg @ref LL_RCC_PLLSAIM_DIV_39 + * @arg @ref LL_RCC_PLLSAIM_DIV_40 + * @arg @ref LL_RCC_PLLSAIM_DIV_41 + * @arg @ref LL_RCC_PLLSAIM_DIV_42 + * @arg @ref LL_RCC_PLLSAIM_DIV_43 + * @arg @ref LL_RCC_PLLSAIM_DIV_44 + * @arg @ref LL_RCC_PLLSAIM_DIV_45 + * @arg @ref LL_RCC_PLLSAIM_DIV_46 + * @arg @ref LL_RCC_PLLSAIM_DIV_47 + * @arg @ref LL_RCC_PLLSAIM_DIV_48 + * @arg @ref LL_RCC_PLLSAIM_DIV_49 + * @arg @ref LL_RCC_PLLSAIM_DIV_50 + * @arg @ref LL_RCC_PLLSAIM_DIV_51 + * @arg @ref LL_RCC_PLLSAIM_DIV_52 + * @arg @ref LL_RCC_PLLSAIM_DIV_53 + * @arg @ref LL_RCC_PLLSAIM_DIV_54 + * @arg @ref LL_RCC_PLLSAIM_DIV_55 + * @arg @ref LL_RCC_PLLSAIM_DIV_56 + * @arg @ref LL_RCC_PLLSAIM_DIV_57 + * @arg @ref LL_RCC_PLLSAIM_DIV_58 + * @arg @ref LL_RCC_PLLSAIM_DIV_59 + * @arg @ref LL_RCC_PLLSAIM_DIV_60 + * @arg @ref LL_RCC_PLLSAIM_DIV_61 + * @arg @ref LL_RCC_PLLSAIM_DIV_62 + * @arg @ref LL_RCC_PLLSAIM_DIV_63 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDivider(void) +{ +#if defined(RCC_PLLSAICFGR_PLLSAIM) + return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM)); +#else + return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); +#endif /* RCC_PLLSAICFGR_PLLSAIM */ +} + +/** + * @brief Get SAIPLL multiplication factor for VCO + * @rmtoll PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_GetN + * @retval Between 49/50(*) and 432 + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetN(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); +} + +/** + * @brief Get SAIPLL division factor for PLLSAIQ + * @rmtoll PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_GetQ + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIQ_DIV_15 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetQ(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIQ)); +} + +#if defined(RCC_PLLSAICFGR_PLLSAIR) +/** + * @brief Get SAIPLL division factor for PLLSAIR + * @note used for PLLSAICLK (SAI clock) + * @rmtoll PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_GetR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIR_DIV_2 + * @arg @ref LL_RCC_PLLSAIR_DIV_3 + * @arg @ref LL_RCC_PLLSAIR_DIV_4 + * @arg @ref LL_RCC_PLLSAIR_DIV_5 + * @arg @ref LL_RCC_PLLSAIR_DIV_6 + * @arg @ref LL_RCC_PLLSAIR_DIV_7 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetR(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIR)); +} +#endif /* RCC_PLLSAICFGR_PLLSAIR */ + +#if defined(RCC_PLLSAICFGR_PLLSAIP) +/** + * @brief Get SAIPLL division factor for PLLSAIP + * @note used for PLL48MCLK (48M domain clock) + * @rmtoll PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_GetP + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIP_DIV_2 + * @arg @ref LL_RCC_PLLSAIP_DIV_4 + * @arg @ref LL_RCC_PLLSAIP_DIV_6 + * @arg @ref LL_RCC_PLLSAIP_DIV_8 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetP(void) +{ + return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIP)); +} +#endif /* RCC_PLLSAICFGR_PLLSAIP */ + +/** + * @brief Get SAIPLL division factor for PLLSAIDIVQ + * @note used PLLSAICLK selected (SAI clock) + * @rmtoll DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_GetDIVQ + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 + * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVQ(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ)); +} + +#if defined(RCC_DCKCFGR_PLLSAIDIVR) +/** + * @brief Get SAIPLL division factor for PLLSAIDIVR + * @note used for LTDC domain clock + * @rmtoll DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_GetDIVR + * @retval Returned value can be one of the following values: + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 + * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 + */ +__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVR(void) +{ + return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR)); +} +#endif /* RCC_DCKCFGR_PLLSAIDIVR */ + +/** + * @} + */ +#endif /* RCC_PLLSAI_SUPPORT */ + +/** @defgroup RCC_LL_EF_FLAG_Management FLAG Management + * @{ + */ + +/** + * @brief Clear LSI ready interrupt flag + * @rmtoll CIR LSIRDYC LL_RCC_ClearFlag_LSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_LSIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC); +} + +/** + * @brief Clear LSE ready interrupt flag + * @rmtoll CIR LSERDYC LL_RCC_ClearFlag_LSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_LSERDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_LSERDYC); +} + +/** + * @brief Clear HSI ready interrupt flag + * @rmtoll CIR HSIRDYC LL_RCC_ClearFlag_HSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_HSIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_HSIRDYC); +} + +/** + * @brief Clear HSE ready interrupt flag + * @rmtoll CIR HSERDYC LL_RCC_ClearFlag_HSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_HSERDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_HSERDYC); +} + +/** + * @brief Clear PLL ready interrupt flag + * @rmtoll CIR PLLRDYC LL_RCC_ClearFlag_PLLRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_PLLRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLRDYC); +} + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Clear PLLI2S ready interrupt flag + * @rmtoll CIR PLLI2SRDYC LL_RCC_ClearFlag_PLLI2SRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_PLLI2SRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); +} + +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Clear PLLSAI ready interrupt flag + * @rmtoll CIR PLLSAIRDYC LL_RCC_ClearFlag_PLLSAIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_PLLSAIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); +} + +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @brief Clear Clock security system interrupt flag + * @rmtoll CIR CSSC LL_RCC_ClearFlag_HSECSS + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearFlag_HSECSS(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_CSSC); +} + +/** + * @brief Check if LSI ready interrupt occurred or not + * @rmtoll CIR LSIRDYF LL_RCC_IsActiveFlag_LSIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYF) == (RCC_CIR_LSIRDYF)); +} + +/** + * @brief Check if LSE ready interrupt occurred or not + * @rmtoll CIR LSERDYF LL_RCC_IsActiveFlag_LSERDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSERDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYF) == (RCC_CIR_LSERDYF)); +} + +/** + * @brief Check if HSI ready interrupt occurred or not + * @rmtoll CIR HSIRDYF LL_RCC_IsActiveFlag_HSIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYF) == (RCC_CIR_HSIRDYF)); +} + +/** + * @brief Check if HSE ready interrupt occurred or not + * @rmtoll CIR HSERDYF LL_RCC_IsActiveFlag_HSERDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSERDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYF) == (RCC_CIR_HSERDYF)); +} + +/** + * @brief Check if PLL ready interrupt occurred or not + * @rmtoll CIR PLLRDYF LL_RCC_IsActiveFlag_PLLRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYF) == (RCC_CIR_PLLRDYF)); +} + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Check if PLLI2S ready interrupt occurred or not + * @rmtoll CIR PLLI2SRDYF LL_RCC_IsActiveFlag_PLLI2SRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLI2SRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYF) == (RCC_CIR_PLLI2SRDYF)); +} +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Check if PLLSAI ready interrupt occurred or not + * @rmtoll CIR PLLSAIRDYF LL_RCC_IsActiveFlag_PLLSAIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLSAIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYF) == (RCC_CIR_PLLSAIRDYF)); +} +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @brief Check if Clock security system interrupt occurred or not + * @rmtoll CIR CSSF LL_RCC_IsActiveFlag_HSECSS + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSECSS(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_CSSF) == (RCC_CIR_CSSF)); +} + +/** + * @brief Check if RCC flag Independent Watchdog reset is set or not. + * @rmtoll CSR IWDGRSTF LL_RCC_IsActiveFlag_IWDGRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_IWDGRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_IWDGRSTF) == (RCC_CSR_IWDGRSTF)); +} + +/** + * @brief Check if RCC flag Low Power reset is set or not. + * @rmtoll CSR LPWRRSTF LL_RCC_IsActiveFlag_LPWRRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LPWRRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_LPWRRSTF) == (RCC_CSR_LPWRRSTF)); +} + +/** + * @brief Check if RCC flag Pin reset is set or not. + * @rmtoll CSR PINRSTF LL_RCC_IsActiveFlag_PINRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PINRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_PINRSTF) == (RCC_CSR_PINRSTF)); +} + +/** + * @brief Check if RCC flag POR/PDR reset is set or not. + * @rmtoll CSR PORRSTF LL_RCC_IsActiveFlag_PORRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PORRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_PORRSTF) == (RCC_CSR_PORRSTF)); +} + +/** + * @brief Check if RCC flag Software reset is set or not. + * @rmtoll CSR SFTRSTF LL_RCC_IsActiveFlag_SFTRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_SFTRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_SFTRSTF) == (RCC_CSR_SFTRSTF)); +} + +/** + * @brief Check if RCC flag Window Watchdog reset is set or not. + * @rmtoll CSR WWDGRSTF LL_RCC_IsActiveFlag_WWDGRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_WWDGRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_WWDGRSTF) == (RCC_CSR_WWDGRSTF)); +} + +#if defined(RCC_CSR_BORRSTF) +/** + * @brief Check if RCC flag BOR reset is set or not. + * @rmtoll CSR BORRSTF LL_RCC_IsActiveFlag_BORRST + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_BORRST(void) +{ + return (READ_BIT(RCC->CSR, RCC_CSR_BORRSTF) == (RCC_CSR_BORRSTF)); +} +#endif /* RCC_CSR_BORRSTF */ + +/** + * @brief Set RMVF bit to clear the reset flags. + * @rmtoll CSR RMVF LL_RCC_ClearResetFlags + * @retval None + */ +__STATIC_INLINE void LL_RCC_ClearResetFlags(void) +{ + SET_BIT(RCC->CSR, RCC_CSR_RMVF); +} + +/** + * @} + */ + +/** @defgroup RCC_LL_EF_IT_Management IT Management + * @{ + */ + +/** + * @brief Enable LSI ready interrupt + * @rmtoll CIR LSIRDYIE LL_RCC_EnableIT_LSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_LSIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); +} + +/** + * @brief Enable LSE ready interrupt + * @rmtoll CIR LSERDYIE LL_RCC_EnableIT_LSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_LSERDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_LSERDYIE); +} + +/** + * @brief Enable HSI ready interrupt + * @rmtoll CIR HSIRDYIE LL_RCC_EnableIT_HSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_HSIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); +} + +/** + * @brief Enable HSE ready interrupt + * @rmtoll CIR HSERDYIE LL_RCC_EnableIT_HSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_HSERDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_HSERDYIE); +} + +/** + * @brief Enable PLL ready interrupt + * @rmtoll CIR PLLRDYIE LL_RCC_EnableIT_PLLRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_PLLRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); +} + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Enable PLLI2S ready interrupt + * @rmtoll CIR PLLI2SRDYIE LL_RCC_EnableIT_PLLI2SRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_PLLI2SRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); +} +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Enable PLLSAI ready interrupt + * @rmtoll CIR PLLSAIRDYIE LL_RCC_EnableIT_PLLSAIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_EnableIT_PLLSAIRDY(void) +{ + SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); +} +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @brief Disable LSI ready interrupt + * @rmtoll CIR LSIRDYIE LL_RCC_DisableIT_LSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_LSIRDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); +} + +/** + * @brief Disable LSE ready interrupt + * @rmtoll CIR LSERDYIE LL_RCC_DisableIT_LSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_LSERDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_LSERDYIE); +} + +/** + * @brief Disable HSI ready interrupt + * @rmtoll CIR HSIRDYIE LL_RCC_DisableIT_HSIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_HSIRDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); +} + +/** + * @brief Disable HSE ready interrupt + * @rmtoll CIR HSERDYIE LL_RCC_DisableIT_HSERDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_HSERDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_HSERDYIE); +} + +/** + * @brief Disable PLL ready interrupt + * @rmtoll CIR PLLRDYIE LL_RCC_DisableIT_PLLRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_PLLRDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); +} + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Disable PLLI2S ready interrupt + * @rmtoll CIR PLLI2SRDYIE LL_RCC_DisableIT_PLLI2SRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_PLLI2SRDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); +} + +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Disable PLLSAI ready interrupt + * @rmtoll CIR PLLSAIRDYIE LL_RCC_DisableIT_PLLSAIRDY + * @retval None + */ +__STATIC_INLINE void LL_RCC_DisableIT_PLLSAIRDY(void) +{ + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); +} +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @brief Checks if LSI ready interrupt source is enabled or disabled. + * @rmtoll CIR LSIRDYIE LL_RCC_IsEnabledIT_LSIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYIE) == (RCC_CIR_LSIRDYIE)); +} + +/** + * @brief Checks if LSE ready interrupt source is enabled or disabled. + * @rmtoll CIR LSERDYIE LL_RCC_IsEnabledIT_LSERDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSERDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYIE) == (RCC_CIR_LSERDYIE)); +} + +/** + * @brief Checks if HSI ready interrupt source is enabled or disabled. + * @rmtoll CIR HSIRDYIE LL_RCC_IsEnabledIT_HSIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYIE) == (RCC_CIR_HSIRDYIE)); +} + +/** + * @brief Checks if HSE ready interrupt source is enabled or disabled. + * @rmtoll CIR HSERDYIE LL_RCC_IsEnabledIT_HSERDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSERDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYIE) == (RCC_CIR_HSERDYIE)); +} + +/** + * @brief Checks if PLL ready interrupt source is enabled or disabled. + * @rmtoll CIR PLLRDYIE LL_RCC_IsEnabledIT_PLLRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYIE) == (RCC_CIR_PLLRDYIE)); +} + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Checks if PLLI2S ready interrupt source is enabled or disabled. + * @rmtoll CIR PLLI2SRDYIE LL_RCC_IsEnabledIT_PLLI2SRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLI2SRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE) == (RCC_CIR_PLLI2SRDYIE)); +} + +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Checks if PLLSAI ready interrupt source is enabled or disabled. + * @rmtoll CIR PLLSAIRDYIE LL_RCC_IsEnabledIT_PLLSAIRDY + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLSAIRDY(void) +{ + return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE) == (RCC_CIR_PLLSAIRDYIE)); +} +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup RCC_LL_EF_Init De-initialization function + * @{ + */ +ErrorStatus LL_RCC_DeInit(void); +/** + * @} + */ + +/** @defgroup RCC_LL_EF_Get_Freq Get system and peripherals clocks frequency functions + * @{ + */ +void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks); +#if defined(FMPI2C1) +uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource); +#endif /* FMPI2C1 */ +#if defined(LPTIM1) +uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource); +#endif /* LPTIM1 */ +#if defined(SAI1) +uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource); +#endif /* SAI1 */ +#if defined(SDIO) +uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource); +#endif /* SDIO */ +#if defined(RNG) +uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource); +#endif /* RNG */ +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource); +#endif /* USB_OTG_FS || USB_OTG_HS */ +#if defined(DFSDM1_Channel0) +uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource); +uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource); +#endif /* DFSDM1_Channel0 */ +uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource); +#if defined(CEC) +uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource); +#endif /* CEC */ +#if defined(LTDC) +uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource); +#endif /* LTDC */ +#if defined(SPDIFRX) +uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource); +#endif /* SPDIFRX */ +#if defined(DSI) +uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource); +#endif /* DSI */ +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(RCC) */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_RCC_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h new file mode 100644 index 0000000..3a09800 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h @@ -0,0 +1,2027 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_spi.h + * @author MCD Application Team + * @brief Header file of SPI LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_LL_SPI_H +#define STM32F4xx_LL_SPI_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) + +/** @defgroup SPI_LL SPI + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup SPI_LL_ES_INIT SPI Exported Init structure + * @{ + */ + +/** + * @brief SPI Init structures definition + */ +typedef struct +{ + uint32_t TransferDirection; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_LL_EC_TRANSFER_MODE. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferDirection().*/ + + uint32_t Mode; /*!< Specifies the SPI mode (Master/Slave). + This parameter can be a value of @ref SPI_LL_EC_MODE. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetMode().*/ + + uint32_t DataWidth; /*!< Specifies the SPI data width. + This parameter can be a value of @ref SPI_LL_EC_DATAWIDTH. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetDataWidth().*/ + + uint32_t ClockPolarity; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_LL_EC_POLARITY. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPolarity().*/ + + uint32_t ClockPhase; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_LL_EC_PHASE. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPhase().*/ + + uint32_t NSS; /*!< Specifies whether the NSS signal is managed by hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_LL_EC_NSS_MODE. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetNSSMode().*/ + + uint32_t BaudRate; /*!< Specifies the BaudRate prescaler value which will be used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_LL_EC_BAUDRATEPRESCALER. + @note The communication clock is derived from the master clock. The slave clock does not need to be set. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetBaudRatePrescaler().*/ + + uint32_t BitOrder; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_LL_EC_BIT_ORDER. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferBitOrder().*/ + + uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. + This parameter can be a value of @ref SPI_LL_EC_CRC_CALCULATION. + + This feature can be modified afterwards using unitary functions @ref LL_SPI_EnableCRC() and @ref LL_SPI_DisableCRC().*/ + + uint32_t CRCPoly; /*!< Specifies the polynomial used for the CRC calculation. + This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF. + + This feature can be modified afterwards using unitary function @ref LL_SPI_SetCRCPolynomial().*/ + +} LL_SPI_InitTypeDef; + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup SPI_LL_Exported_Constants SPI Exported Constants + * @{ + */ + +/** @defgroup SPI_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_SPI_ReadReg function + * @{ + */ +#define LL_SPI_SR_RXNE SPI_SR_RXNE /*!< Rx buffer not empty flag */ +#define LL_SPI_SR_TXE SPI_SR_TXE /*!< Tx buffer empty flag */ +#define LL_SPI_SR_BSY SPI_SR_BSY /*!< Busy flag */ +#define LL_SPI_SR_CRCERR SPI_SR_CRCERR /*!< CRC error flag */ +#define LL_SPI_SR_MODF SPI_SR_MODF /*!< Mode fault flag */ +#define LL_SPI_SR_OVR SPI_SR_OVR /*!< Overrun flag */ +#define LL_SPI_SR_FRE SPI_SR_FRE /*!< TI mode frame format error flag */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions + * @{ + */ +#define LL_SPI_CR2_RXNEIE SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ +#define LL_SPI_CR2_TXEIE SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ +#define LL_SPI_CR2_ERRIE SPI_CR2_ERRIE /*!< Error interrupt enable */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_MODE Operation Mode + * @{ + */ +#define LL_SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) /*!< Master configuration */ +#define LL_SPI_MODE_SLAVE 0x00000000U /*!< Slave configuration */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_PROTOCOL Serial Protocol + * @{ + */ +#define LL_SPI_PROTOCOL_MOTOROLA 0x00000000U /*!< Motorola mode. Used as default value */ +#define LL_SPI_PROTOCOL_TI (SPI_CR2_FRF) /*!< TI mode */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_PHASE Clock Phase + * @{ + */ +#define LL_SPI_PHASE_1EDGE 0x00000000U /*!< First clock transition is the first data capture edge */ +#define LL_SPI_PHASE_2EDGE (SPI_CR1_CPHA) /*!< Second clock transition is the first data capture edge */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_POLARITY Clock Polarity + * @{ + */ +#define LL_SPI_POLARITY_LOW 0x00000000U /*!< Clock to 0 when idle */ +#define LL_SPI_POLARITY_HIGH (SPI_CR1_CPOL) /*!< Clock to 1 when idle */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_BAUDRATEPRESCALER Baud Rate Prescaler + * @{ + */ +#define LL_SPI_BAUDRATEPRESCALER_DIV2 0x00000000U /*!< BaudRate control equal to fPCLK/2 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV4 (SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/4 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV8 (SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/8 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/16 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV32 (SPI_CR1_BR_2) /*!< BaudRate control equal to fPCLK/32 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/64 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/128 */ +#define LL_SPI_BAUDRATEPRESCALER_DIV256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/256 */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_BIT_ORDER Transmission Bit Order + * @{ + */ +#define LL_SPI_LSB_FIRST (SPI_CR1_LSBFIRST) /*!< Data is transmitted/received with the LSB first */ +#define LL_SPI_MSB_FIRST 0x00000000U /*!< Data is transmitted/received with the MSB first */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_TRANSFER_MODE Transfer Mode + * @{ + */ +#define LL_SPI_FULL_DUPLEX 0x00000000U /*!< Full-Duplex mode. Rx and Tx transfer on 2 lines */ +#define LL_SPI_SIMPLEX_RX (SPI_CR1_RXONLY) /*!< Simplex Rx mode. Rx transfer only on 1 line */ +#define LL_SPI_HALF_DUPLEX_RX (SPI_CR1_BIDIMODE) /*!< Half-Duplex Rx mode. Rx transfer on 1 line */ +#define LL_SPI_HALF_DUPLEX_TX (SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE) /*!< Half-Duplex Tx mode. Tx transfer on 1 line */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_NSS_MODE Slave Select Pin Mode + * @{ + */ +#define LL_SPI_NSS_SOFT (SPI_CR1_SSM) /*!< NSS managed internally. NSS pin not used and free */ +#define LL_SPI_NSS_HARD_INPUT 0x00000000U /*!< NSS pin used in Input. Only used in Master mode */ +#define LL_SPI_NSS_HARD_OUTPUT (((uint32_t)SPI_CR2_SSOE << 16U)) /*!< NSS pin used in Output. Only used in Slave mode as chip select */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_DATAWIDTH Datawidth + * @{ + */ +#define LL_SPI_DATAWIDTH_8BIT 0x00000000U /*!< Data length for SPI transfer: 8 bits */ +#define LL_SPI_DATAWIDTH_16BIT (SPI_CR1_DFF) /*!< Data length for SPI transfer: 16 bits */ +/** + * @} + */ +#if defined(USE_FULL_LL_DRIVER) + +/** @defgroup SPI_LL_EC_CRC_CALCULATION CRC Calculation + * @{ + */ +#define LL_SPI_CRCCALCULATION_DISABLE 0x00000000U /*!< CRC calculation disabled */ +#define LL_SPI_CRCCALCULATION_ENABLE (SPI_CR1_CRCEN) /*!< CRC calculation enabled */ +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup SPI_LL_Exported_Macros SPI Exported Macros + * @{ + */ + +/** @defgroup SPI_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in SPI register + * @param __INSTANCE__ SPI Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_SPI_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in SPI register + * @param __INSTANCE__ SPI Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_SPI_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SPI_LL_Exported_Functions SPI Exported Functions + * @{ + */ + +/** @defgroup SPI_LL_EF_Configuration Configuration + * @{ + */ + +/** + * @brief Enable SPI peripheral + * @rmtoll CR1 SPE LL_SPI_Enable + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_Enable(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR1, SPI_CR1_SPE); +} + +/** + * @brief Disable SPI peripheral + * @note When disabling the SPI, follow the procedure described in the Reference Manual. + * @rmtoll CR1 SPE LL_SPI_Disable + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_Disable(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); +} + +/** + * @brief Check if SPI peripheral is enabled + * @rmtoll CR1 SPE LL_SPI_IsEnabled + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabled(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR1, SPI_CR1_SPE) == (SPI_CR1_SPE)) ? 1UL : 0UL); +} + +/** + * @brief Set SPI operation mode to Master or Slave + * @note This bit should not be changed when communication is ongoing. + * @rmtoll CR1 MSTR LL_SPI_SetMode\n + * CR1 SSI LL_SPI_SetMode + * @param SPIx SPI Instance + * @param Mode This parameter can be one of the following values: + * @arg @ref LL_SPI_MODE_MASTER + * @arg @ref LL_SPI_MODE_SLAVE + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetMode(SPI_TypeDef *SPIx, uint32_t Mode) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI, Mode); +} + +/** + * @brief Get SPI operation mode (Master or Slave) + * @rmtoll CR1 MSTR LL_SPI_GetMode\n + * CR1 SSI LL_SPI_GetMode + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_MODE_MASTER + * @arg @ref LL_SPI_MODE_SLAVE + */ +__STATIC_INLINE uint32_t LL_SPI_GetMode(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI)); +} + +/** + * @brief Set serial protocol used + * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. + * @rmtoll CR2 FRF LL_SPI_SetStandard + * @param SPIx SPI Instance + * @param Standard This parameter can be one of the following values: + * @arg @ref LL_SPI_PROTOCOL_MOTOROLA + * @arg @ref LL_SPI_PROTOCOL_TI + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) +{ + MODIFY_REG(SPIx->CR2, SPI_CR2_FRF, Standard); +} + +/** + * @brief Get serial protocol used + * @rmtoll CR2 FRF LL_SPI_GetStandard + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_PROTOCOL_MOTOROLA + * @arg @ref LL_SPI_PROTOCOL_TI + */ +__STATIC_INLINE uint32_t LL_SPI_GetStandard(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_FRF)); +} + +/** + * @brief Set clock phase + * @note This bit should not be changed when communication is ongoing. + * This bit is not used in SPI TI mode. + * @rmtoll CR1 CPHA LL_SPI_SetClockPhase + * @param SPIx SPI Instance + * @param ClockPhase This parameter can be one of the following values: + * @arg @ref LL_SPI_PHASE_1EDGE + * @arg @ref LL_SPI_PHASE_2EDGE + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetClockPhase(SPI_TypeDef *SPIx, uint32_t ClockPhase) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_CPHA, ClockPhase); +} + +/** + * @brief Get clock phase + * @rmtoll CR1 CPHA LL_SPI_GetClockPhase + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_PHASE_1EDGE + * @arg @ref LL_SPI_PHASE_2EDGE + */ +__STATIC_INLINE uint32_t LL_SPI_GetClockPhase(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPHA)); +} + +/** + * @brief Set clock polarity + * @note This bit should not be changed when communication is ongoing. + * This bit is not used in SPI TI mode. + * @rmtoll CR1 CPOL LL_SPI_SetClockPolarity + * @param SPIx SPI Instance + * @param ClockPolarity This parameter can be one of the following values: + * @arg @ref LL_SPI_POLARITY_LOW + * @arg @ref LL_SPI_POLARITY_HIGH + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_CPOL, ClockPolarity); +} + +/** + * @brief Get clock polarity + * @rmtoll CR1 CPOL LL_SPI_GetClockPolarity + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_POLARITY_LOW + * @arg @ref LL_SPI_POLARITY_HIGH + */ +__STATIC_INLINE uint32_t LL_SPI_GetClockPolarity(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPOL)); +} + +/** + * @brief Set baud rate prescaler + * @note These bits should not be changed when communication is ongoing. SPI BaudRate = fPCLK/Prescaler. + * @rmtoll CR1 BR LL_SPI_SetBaudRatePrescaler + * @param SPIx SPI Instance + * @param BaudRate This parameter can be one of the following values: + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetBaudRatePrescaler(SPI_TypeDef *SPIx, uint32_t BaudRate) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_BR, BaudRate); +} + +/** + * @brief Get baud rate prescaler + * @rmtoll CR1 BR LL_SPI_GetBaudRatePrescaler + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 + * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 + */ +__STATIC_INLINE uint32_t LL_SPI_GetBaudRatePrescaler(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_BR)); +} + +/** + * @brief Set transfer bit order + * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode. + * @rmtoll CR1 LSBFIRST LL_SPI_SetTransferBitOrder + * @param SPIx SPI Instance + * @param BitOrder This parameter can be one of the following values: + * @arg @ref LL_SPI_LSB_FIRST + * @arg @ref LL_SPI_MSB_FIRST + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetTransferBitOrder(SPI_TypeDef *SPIx, uint32_t BitOrder) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_LSBFIRST, BitOrder); +} + +/** + * @brief Get transfer bit order + * @rmtoll CR1 LSBFIRST LL_SPI_GetTransferBitOrder + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_LSB_FIRST + * @arg @ref LL_SPI_MSB_FIRST + */ +__STATIC_INLINE uint32_t LL_SPI_GetTransferBitOrder(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_LSBFIRST)); +} + +/** + * @brief Set transfer direction mode + * @note For Half-Duplex mode, Rx Direction is set by default. + * In master mode, the MOSI pin is used and in slave mode, the MISO pin is used for Half-Duplex. + * @rmtoll CR1 RXONLY LL_SPI_SetTransferDirection\n + * CR1 BIDIMODE LL_SPI_SetTransferDirection\n + * CR1 BIDIOE LL_SPI_SetTransferDirection + * @param SPIx SPI Instance + * @param TransferDirection This parameter can be one of the following values: + * @arg @ref LL_SPI_FULL_DUPLEX + * @arg @ref LL_SPI_SIMPLEX_RX + * @arg @ref LL_SPI_HALF_DUPLEX_RX + * @arg @ref LL_SPI_HALF_DUPLEX_TX + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetTransferDirection(SPI_TypeDef *SPIx, uint32_t TransferDirection) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE, TransferDirection); +} + +/** + * @brief Get transfer direction mode + * @rmtoll CR1 RXONLY LL_SPI_GetTransferDirection\n + * CR1 BIDIMODE LL_SPI_GetTransferDirection\n + * CR1 BIDIOE LL_SPI_GetTransferDirection + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_FULL_DUPLEX + * @arg @ref LL_SPI_SIMPLEX_RX + * @arg @ref LL_SPI_HALF_DUPLEX_RX + * @arg @ref LL_SPI_HALF_DUPLEX_TX + */ +__STATIC_INLINE uint32_t LL_SPI_GetTransferDirection(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE)); +} + +/** + * @brief Set frame data width + * @rmtoll CR1 DFF LL_SPI_SetDataWidth + * @param SPIx SPI Instance + * @param DataWidth This parameter can be one of the following values: + * @arg @ref LL_SPI_DATAWIDTH_8BIT + * @arg @ref LL_SPI_DATAWIDTH_16BIT + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetDataWidth(SPI_TypeDef *SPIx, uint32_t DataWidth) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_DFF, DataWidth); +} + +/** + * @brief Get frame data width + * @rmtoll CR1 DFF LL_SPI_GetDataWidth + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_DATAWIDTH_8BIT + * @arg @ref LL_SPI_DATAWIDTH_16BIT + */ +__STATIC_INLINE uint32_t LL_SPI_GetDataWidth(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_DFF)); +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_CRC_Management CRC Management + * @{ + */ + +/** + * @brief Enable CRC + * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. + * @rmtoll CR1 CRCEN LL_SPI_EnableCRC + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableCRC(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR1, SPI_CR1_CRCEN); +} + +/** + * @brief Disable CRC + * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. + * @rmtoll CR1 CRCEN LL_SPI_DisableCRC + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableCRC(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR1, SPI_CR1_CRCEN); +} + +/** + * @brief Check if CRC is enabled + * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. + * @rmtoll CR1 CRCEN LL_SPI_IsEnabledCRC + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledCRC(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR1, SPI_CR1_CRCEN) == (SPI_CR1_CRCEN)) ? 1UL : 0UL); +} + +/** + * @brief Set CRCNext to transfer CRC on the line + * @note This bit has to be written as soon as the last data is written in the SPIx_DR register. + * @rmtoll CR1 CRCNEXT LL_SPI_SetCRCNext + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetCRCNext(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR1, SPI_CR1_CRCNEXT); +} + +/** + * @brief Set polynomial for CRC calculation + * @rmtoll CRCPR CRCPOLY LL_SPI_SetCRCPolynomial + * @param SPIx SPI Instance + * @param CRCPoly This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetCRCPolynomial(SPI_TypeDef *SPIx, uint32_t CRCPoly) +{ + WRITE_REG(SPIx->CRCPR, (uint16_t)CRCPoly); +} + +/** + * @brief Get polynomial for CRC calculation + * @rmtoll CRCPR CRCPOLY LL_SPI_GetCRCPolynomial + * @param SPIx SPI Instance + * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF + */ +__STATIC_INLINE uint32_t LL_SPI_GetCRCPolynomial(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_REG(SPIx->CRCPR)); +} + +/** + * @brief Get Rx CRC + * @rmtoll RXCRCR RXCRC LL_SPI_GetRxCRC + * @param SPIx SPI Instance + * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF + */ +__STATIC_INLINE uint32_t LL_SPI_GetRxCRC(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_REG(SPIx->RXCRCR)); +} + +/** + * @brief Get Tx CRC + * @rmtoll TXCRCR TXCRC LL_SPI_GetTxCRC + * @param SPIx SPI Instance + * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF + */ +__STATIC_INLINE uint32_t LL_SPI_GetTxCRC(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_REG(SPIx->TXCRCR)); +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_NSS_Management Slave Select Pin Management + * @{ + */ + +/** + * @brief Set NSS mode + * @note LL_SPI_NSS_SOFT Mode is not used in SPI TI mode. + * @rmtoll CR1 SSM LL_SPI_SetNSSMode\n + * @rmtoll CR2 SSOE LL_SPI_SetNSSMode + * @param SPIx SPI Instance + * @param NSS This parameter can be one of the following values: + * @arg @ref LL_SPI_NSS_SOFT + * @arg @ref LL_SPI_NSS_HARD_INPUT + * @arg @ref LL_SPI_NSS_HARD_OUTPUT + * @retval None + */ +__STATIC_INLINE void LL_SPI_SetNSSMode(SPI_TypeDef *SPIx, uint32_t NSS) +{ + MODIFY_REG(SPIx->CR1, SPI_CR1_SSM, NSS); + MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, ((uint32_t)(NSS >> 16U))); +} + +/** + * @brief Get NSS mode + * @rmtoll CR1 SSM LL_SPI_GetNSSMode\n + * @rmtoll CR2 SSOE LL_SPI_GetNSSMode + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_SPI_NSS_SOFT + * @arg @ref LL_SPI_NSS_HARD_INPUT + * @arg @ref LL_SPI_NSS_HARD_OUTPUT + */ +__STATIC_INLINE uint32_t LL_SPI_GetNSSMode(SPI_TypeDef *SPIx) +{ + uint32_t Ssm = (READ_BIT(SPIx->CR1, SPI_CR1_SSM)); + uint32_t Ssoe = (READ_BIT(SPIx->CR2, SPI_CR2_SSOE) << 16U); + return (Ssm | Ssoe); +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_FLAG_Management FLAG Management + * @{ + */ + +/** + * @brief Check if Rx buffer is not empty + * @rmtoll SR RXNE LL_SPI_IsActiveFlag_RXNE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_RXNE) == (SPI_SR_RXNE)) ? 1UL : 0UL); +} + +/** + * @brief Check if Tx buffer is empty + * @rmtoll SR TXE LL_SPI_IsActiveFlag_TXE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_TXE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_TXE) == (SPI_SR_TXE)) ? 1UL : 0UL); +} + +/** + * @brief Get CRC error flag + * @rmtoll SR CRCERR LL_SPI_IsActiveFlag_CRCERR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_CRCERR(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_CRCERR) == (SPI_SR_CRCERR)) ? 1UL : 0UL); +} + +/** + * @brief Get mode fault error flag + * @rmtoll SR MODF LL_SPI_IsActiveFlag_MODF + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_MODF(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_MODF) == (SPI_SR_MODF)) ? 1UL : 0UL); +} + +/** + * @brief Get overrun error flag + * @rmtoll SR OVR LL_SPI_IsActiveFlag_OVR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_OVR(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_OVR) == (SPI_SR_OVR)) ? 1UL : 0UL); +} + +/** + * @brief Get busy flag + * @note The BSY flag is cleared under any one of the following conditions: + * -When the SPI is correctly disabled + * -When a fault is detected in Master mode (MODF bit set to 1) + * -In Master mode, when it finishes a data transmission and no new data is ready to be + * sent + * -In Slave mode, when the BSY flag is set to '0' for at least one SPI clock cycle between + * each data transfer. + * @rmtoll SR BSY LL_SPI_IsActiveFlag_BSY + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_BSY(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_BSY) == (SPI_SR_BSY)) ? 1UL : 0UL); +} + +/** + * @brief Get frame format error flag + * @rmtoll SR FRE LL_SPI_IsActiveFlag_FRE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_FRE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_FRE) == (SPI_SR_FRE)) ? 1UL : 0UL); +} + +/** + * @brief Clear CRC error flag + * @rmtoll SR CRCERR LL_SPI_ClearFlag_CRCERR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_ClearFlag_CRCERR(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->SR, SPI_SR_CRCERR); +} + +/** + * @brief Clear mode fault error flag + * @note Clearing this flag is done by a read access to the SPIx_SR + * register followed by a write access to the SPIx_CR1 register + * @rmtoll SR MODF LL_SPI_ClearFlag_MODF + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_ClearFlag_MODF(SPI_TypeDef *SPIx) +{ + __IO uint32_t tmpreg_sr; + tmpreg_sr = SPIx->SR; + (void) tmpreg_sr; + CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); +} + +/** + * @brief Clear overrun error flag + * @note Clearing this flag is done by a read access to the SPIx_DR + * register followed by a read access to the SPIx_SR register + * @rmtoll SR OVR LL_SPI_ClearFlag_OVR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_ClearFlag_OVR(SPI_TypeDef *SPIx) +{ + __IO uint32_t tmpreg; + tmpreg = SPIx->DR; + (void) tmpreg; + tmpreg = SPIx->SR; + (void) tmpreg; +} + +/** + * @brief Clear frame format error flag + * @note Clearing this flag is done by reading SPIx_SR register + * @rmtoll SR FRE LL_SPI_ClearFlag_FRE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_ClearFlag_FRE(SPI_TypeDef *SPIx) +{ + __IO uint32_t tmpreg; + tmpreg = SPIx->SR; + (void) tmpreg; +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_IT_Management Interrupt Management + * @{ + */ + +/** + * @brief Enable error interrupt + * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). + * @rmtoll CR2 ERRIE LL_SPI_EnableIT_ERR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableIT_ERR(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR2, SPI_CR2_ERRIE); +} + +/** + * @brief Enable Rx buffer not empty interrupt + * @rmtoll CR2 RXNEIE LL_SPI_EnableIT_RXNE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableIT_RXNE(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR2, SPI_CR2_RXNEIE); +} + +/** + * @brief Enable Tx buffer empty interrupt + * @rmtoll CR2 TXEIE LL_SPI_EnableIT_TXE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableIT_TXE(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR2, SPI_CR2_TXEIE); +} + +/** + * @brief Disable error interrupt + * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). + * @rmtoll CR2 ERRIE LL_SPI_DisableIT_ERR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableIT_ERR(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR2, SPI_CR2_ERRIE); +} + +/** + * @brief Disable Rx buffer not empty interrupt + * @rmtoll CR2 RXNEIE LL_SPI_DisableIT_RXNE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableIT_RXNE(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR2, SPI_CR2_RXNEIE); +} + +/** + * @brief Disable Tx buffer empty interrupt + * @rmtoll CR2 TXEIE LL_SPI_DisableIT_TXE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableIT_TXE(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR2, SPI_CR2_TXEIE); +} + +/** + * @brief Check if error interrupt is enabled + * @rmtoll CR2 ERRIE LL_SPI_IsEnabledIT_ERR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_ERR(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR2, SPI_CR2_ERRIE) == (SPI_CR2_ERRIE)) ? 1UL : 0UL); +} + +/** + * @brief Check if Rx buffer not empty interrupt is enabled + * @rmtoll CR2 RXNEIE LL_SPI_IsEnabledIT_RXNE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR2, SPI_CR2_RXNEIE) == (SPI_CR2_RXNEIE)) ? 1UL : 0UL); +} + +/** + * @brief Check if Tx buffer empty interrupt + * @rmtoll CR2 TXEIE LL_SPI_IsEnabledIT_TXE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_TXE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR2, SPI_CR2_TXEIE) == (SPI_CR2_TXEIE)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_DMA_Management DMA Management + * @{ + */ + +/** + * @brief Enable DMA Rx + * @rmtoll CR2 RXDMAEN LL_SPI_EnableDMAReq_RX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); +} + +/** + * @brief Disable DMA Rx + * @rmtoll CR2 RXDMAEN LL_SPI_DisableDMAReq_RX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableDMAReq_RX(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); +} + +/** + * @brief Check if DMA Rx is enabled + * @rmtoll CR2 RXDMAEN LL_SPI_IsEnabledDMAReq_RX + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR2, SPI_CR2_RXDMAEN) == (SPI_CR2_RXDMAEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable DMA Tx + * @rmtoll CR2 TXDMAEN LL_SPI_EnableDMAReq_TX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); +} + +/** + * @brief Disable DMA Tx + * @rmtoll CR2 TXDMAEN LL_SPI_DisableDMAReq_TX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_SPI_DisableDMAReq_TX(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); +} + +/** + * @brief Check if DMA Tx is enabled + * @rmtoll CR2 TXDMAEN LL_SPI_IsEnabledDMAReq_TX + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->CR2, SPI_CR2_TXDMAEN) == (SPI_CR2_TXDMAEN)) ? 1UL : 0UL); +} + +/** + * @brief Get the data register address used for DMA transfer + * @rmtoll DR DR LL_SPI_DMA_GetRegAddr + * @param SPIx SPI Instance + * @retval Address of data register + */ +__STATIC_INLINE uint32_t LL_SPI_DMA_GetRegAddr(SPI_TypeDef *SPIx) +{ + return (uint32_t) &(SPIx->DR); +} + +/** + * @} + */ + +/** @defgroup SPI_LL_EF_DATA_Management DATA Management + * @{ + */ + +/** + * @brief Read 8-Bits in the data register + * @rmtoll DR DR LL_SPI_ReceiveData8 + * @param SPIx SPI Instance + * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_SPI_ReceiveData8(SPI_TypeDef *SPIx) +{ + return (*((__IO uint8_t *)&SPIx->DR)); +} + +/** + * @brief Read 16-Bits in the data register + * @rmtoll DR DR LL_SPI_ReceiveData16 + * @param SPIx SPI Instance + * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFFFF + */ +__STATIC_INLINE uint16_t LL_SPI_ReceiveData16(SPI_TypeDef *SPIx) +{ + return (uint16_t)(READ_REG(SPIx->DR)); +} + +/** + * @brief Write 8-Bits in the data register + * @rmtoll DR DR LL_SPI_TransmitData8 + * @param SPIx SPI Instance + * @param TxData Value between Min_Data=0x00 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_SPI_TransmitData8(SPI_TypeDef *SPIx, uint8_t TxData) +{ +#if defined (__GNUC__) + __IO uint8_t *spidr = ((__IO uint8_t *)&SPIx->DR); + *spidr = TxData; +#else + *((__IO uint8_t *)&SPIx->DR) = TxData; +#endif /* __GNUC__ */ +} + +/** + * @brief Write 16-Bits in the data register + * @rmtoll DR DR LL_SPI_TransmitData16 + * @param SPIx SPI Instance + * @param TxData Value between Min_Data=0x00 and Max_Data=0xFFFF + * @retval None + */ +__STATIC_INLINE void LL_SPI_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) +{ +#if defined (__GNUC__) + __IO uint16_t *spidr = ((__IO uint16_t *)&SPIx->DR); + *spidr = TxData; +#else + SPIx->DR = TxData; +#endif /* __GNUC__ */ +} + +/** + * @} + */ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup SPI_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx); +ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct); +void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct); + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup I2S_LL I2S + * @{ + */ + +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2S_LL_ES_INIT I2S Exported Init structure + * @{ + */ + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + uint32_t Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_LL_EC_MODE + + This feature can be modified afterwards using unitary function @ref LL_I2S_SetTransferMode().*/ + + uint32_t Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_LL_EC_STANDARD + + This feature can be modified afterwards using unitary function @ref LL_I2S_SetStandard().*/ + + + uint32_t DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_LL_EC_DATA_FORMAT + + This feature can be modified afterwards using unitary function @ref LL_I2S_SetDataFormat().*/ + + + uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_LL_EC_MCLK_OUTPUT + + This feature can be modified afterwards using unitary functions @ref LL_I2S_EnableMasterClock() or @ref LL_I2S_DisableMasterClock.*/ + + + uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_LL_EC_AUDIO_FREQ + + Audio Frequency can be modified afterwards using Reference manual formulas to calculate Prescaler Linear, Parity + and unitary functions @ref LL_I2S_SetPrescalerLinear() and @ref LL_I2S_SetPrescalerParity() to set it.*/ + + + uint32_t ClockPolarity; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_LL_EC_POLARITY + + This feature can be modified afterwards using unitary function @ref LL_I2S_SetClockPolarity().*/ + +} LL_I2S_InitTypeDef; + +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup I2S_LL_Exported_Constants I2S Exported Constants + * @{ + */ + +/** @defgroup I2S_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_I2S_ReadReg function + * @{ + */ +#define LL_I2S_SR_RXNE LL_SPI_SR_RXNE /*!< Rx buffer not empty flag */ +#define LL_I2S_SR_TXE LL_SPI_SR_TXE /*!< Tx buffer empty flag */ +#define LL_I2S_SR_BSY LL_SPI_SR_BSY /*!< Busy flag */ +#define LL_I2S_SR_UDR SPI_SR_UDR /*!< Underrun flag */ +#define LL_I2S_SR_OVR LL_SPI_SR_OVR /*!< Overrun flag */ +#define LL_I2S_SR_FRE LL_SPI_SR_FRE /*!< TI mode frame format error flag */ +/** + * @} + */ + +/** @defgroup SPI_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions + * @{ + */ +#define LL_I2S_CR2_RXNEIE LL_SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ +#define LL_I2S_CR2_TXEIE LL_SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ +#define LL_I2S_CR2_ERRIE LL_SPI_CR2_ERRIE /*!< Error interrupt enable */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_DATA_FORMAT Data format + * @{ + */ +#define LL_I2S_DATAFORMAT_16B 0x00000000U /*!< Data length 16 bits, Channel length 16bit */ +#define LL_I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) /*!< Data length 16 bits, Channel length 32bit */ +#define LL_I2S_DATAFORMAT_24B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0) /*!< Data length 24 bits, Channel length 32bit */ +#define LL_I2S_DATAFORMAT_32B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1) /*!< Data length 16 bits, Channel length 32bit */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_POLARITY Clock Polarity + * @{ + */ +#define LL_I2S_POLARITY_LOW 0x00000000U /*!< Clock steady state is low level */ +#define LL_I2S_POLARITY_HIGH (SPI_I2SCFGR_CKPOL) /*!< Clock steady state is high level */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_STANDARD I2s Standard + * @{ + */ +#define LL_I2S_STANDARD_PHILIPS 0x00000000U /*!< I2S standard philips */ +#define LL_I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) /*!< MSB justified standard (left justified) */ +#define LL_I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) /*!< LSB justified standard (right justified) */ +#define LL_I2S_STANDARD_PCM_SHORT (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1) /*!< PCM standard, short frame synchronization */ +#define LL_I2S_STANDARD_PCM_LONG (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC) /*!< PCM standard, long frame synchronization */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_MODE Operation Mode + * @{ + */ +#define LL_I2S_MODE_SLAVE_TX 0x00000000U /*!< Slave Tx configuration */ +#define LL_I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) /*!< Slave Rx configuration */ +#define LL_I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) /*!< Master Tx configuration */ +#define LL_I2S_MODE_MASTER_RX (SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1) /*!< Master Rx configuration */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_PRESCALER_FACTOR Prescaler Factor + * @{ + */ +#define LL_I2S_PRESCALER_PARITY_EVEN 0x00000000U /*!< Odd factor: Real divider value is = I2SDIV * 2 */ +#define LL_I2S_PRESCALER_PARITY_ODD (SPI_I2SPR_ODD >> 8U) /*!< Odd factor: Real divider value is = (I2SDIV * 2)+1 */ +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) + +/** @defgroup I2S_LL_EC_MCLK_OUTPUT MCLK Output + * @{ + */ +#define LL_I2S_MCLK_OUTPUT_DISABLE 0x00000000U /*!< Master clock output is disabled */ +#define LL_I2S_MCLK_OUTPUT_ENABLE (SPI_I2SPR_MCKOE) /*!< Master clock output is enabled */ +/** + * @} + */ + +/** @defgroup I2S_LL_EC_AUDIO_FREQ Audio Frequency + * @{ + */ + +#define LL_I2S_AUDIOFREQ_192K 192000U /*!< Audio Frequency configuration 192000 Hz */ +#define LL_I2S_AUDIOFREQ_96K 96000U /*!< Audio Frequency configuration 96000 Hz */ +#define LL_I2S_AUDIOFREQ_48K 48000U /*!< Audio Frequency configuration 48000 Hz */ +#define LL_I2S_AUDIOFREQ_44K 44100U /*!< Audio Frequency configuration 44100 Hz */ +#define LL_I2S_AUDIOFREQ_32K 32000U /*!< Audio Frequency configuration 32000 Hz */ +#define LL_I2S_AUDIOFREQ_22K 22050U /*!< Audio Frequency configuration 22050 Hz */ +#define LL_I2S_AUDIOFREQ_16K 16000U /*!< Audio Frequency configuration 16000 Hz */ +#define LL_I2S_AUDIOFREQ_11K 11025U /*!< Audio Frequency configuration 11025 Hz */ +#define LL_I2S_AUDIOFREQ_8K 8000U /*!< Audio Frequency configuration 8000 Hz */ +#define LL_I2S_AUDIOFREQ_DEFAULT 2U /*!< Audio Freq not specified. Register I2SDIV = 2 */ +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup I2S_LL_Exported_Macros I2S Exported Macros + * @{ + */ + +/** @defgroup I2S_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in I2S register + * @param __INSTANCE__ I2S Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_I2S_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in I2S register + * @param __INSTANCE__ I2S Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_I2S_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** + * @} + */ + + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup I2S_LL_Exported_Functions I2S Exported Functions + * @{ + */ + +/** @defgroup I2S_LL_EF_Configuration Configuration + * @{ + */ + +/** + * @brief Select I2S mode and Enable I2S peripheral + * @rmtoll I2SCFGR I2SMOD LL_I2S_Enable\n + * I2SCFGR I2SE LL_I2S_Enable + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_Enable(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); +} + +/** + * @brief Disable I2S peripheral + * @rmtoll I2SCFGR I2SE LL_I2S_Disable + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_Disable(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); +} + +/** + * @brief Check if I2S peripheral is enabled + * @rmtoll I2SCFGR I2SE LL_I2S_IsEnabled + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabled(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SE) == (SPI_I2SCFGR_I2SE)) ? 1UL : 0UL); +} + +/** + * @brief Set I2S data frame length + * @rmtoll I2SCFGR DATLEN LL_I2S_SetDataFormat\n + * I2SCFGR CHLEN LL_I2S_SetDataFormat + * @param SPIx SPI Instance + * @param DataFormat This parameter can be one of the following values: + * @arg @ref LL_I2S_DATAFORMAT_16B + * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED + * @arg @ref LL_I2S_DATAFORMAT_24B + * @arg @ref LL_I2S_DATAFORMAT_32B + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetDataFormat(SPI_TypeDef *SPIx, uint32_t DataFormat) +{ + MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN, DataFormat); +} + +/** + * @brief Get I2S data frame length + * @rmtoll I2SCFGR DATLEN LL_I2S_GetDataFormat\n + * I2SCFGR CHLEN LL_I2S_GetDataFormat + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2S_DATAFORMAT_16B + * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED + * @arg @ref LL_I2S_DATAFORMAT_24B + * @arg @ref LL_I2S_DATAFORMAT_32B + */ +__STATIC_INLINE uint32_t LL_I2S_GetDataFormat(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)); +} + +/** + * @brief Set I2S clock polarity + * @rmtoll I2SCFGR CKPOL LL_I2S_SetClockPolarity + * @param SPIx SPI Instance + * @param ClockPolarity This parameter can be one of the following values: + * @arg @ref LL_I2S_POLARITY_LOW + * @arg @ref LL_I2S_POLARITY_HIGH + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) +{ + SET_BIT(SPIx->I2SCFGR, ClockPolarity); +} + +/** + * @brief Get I2S clock polarity + * @rmtoll I2SCFGR CKPOL LL_I2S_GetClockPolarity + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2S_POLARITY_LOW + * @arg @ref LL_I2S_POLARITY_HIGH + */ +__STATIC_INLINE uint32_t LL_I2S_GetClockPolarity(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_CKPOL)); +} + +/** + * @brief Set I2S standard protocol + * @rmtoll I2SCFGR I2SSTD LL_I2S_SetStandard\n + * I2SCFGR PCMSYNC LL_I2S_SetStandard + * @param SPIx SPI Instance + * @param Standard This parameter can be one of the following values: + * @arg @ref LL_I2S_STANDARD_PHILIPS + * @arg @ref LL_I2S_STANDARD_MSB + * @arg @ref LL_I2S_STANDARD_LSB + * @arg @ref LL_I2S_STANDARD_PCM_SHORT + * @arg @ref LL_I2S_STANDARD_PCM_LONG + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) +{ + MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC, Standard); +} + +/** + * @brief Get I2S standard protocol + * @rmtoll I2SCFGR I2SSTD LL_I2S_GetStandard\n + * I2SCFGR PCMSYNC LL_I2S_GetStandard + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2S_STANDARD_PHILIPS + * @arg @ref LL_I2S_STANDARD_MSB + * @arg @ref LL_I2S_STANDARD_LSB + * @arg @ref LL_I2S_STANDARD_PCM_SHORT + * @arg @ref LL_I2S_STANDARD_PCM_LONG + */ +__STATIC_INLINE uint32_t LL_I2S_GetStandard(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC)); +} + +/** + * @brief Set I2S transfer mode + * @rmtoll I2SCFGR I2SCFG LL_I2S_SetTransferMode + * @param SPIx SPI Instance + * @param Mode This parameter can be one of the following values: + * @arg @ref LL_I2S_MODE_SLAVE_TX + * @arg @ref LL_I2S_MODE_SLAVE_RX + * @arg @ref LL_I2S_MODE_MASTER_TX + * @arg @ref LL_I2S_MODE_MASTER_RX + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetTransferMode(SPI_TypeDef *SPIx, uint32_t Mode) +{ + MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG, Mode); +} + +/** + * @brief Get I2S transfer mode + * @rmtoll I2SCFGR I2SCFG LL_I2S_GetTransferMode + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2S_MODE_SLAVE_TX + * @arg @ref LL_I2S_MODE_SLAVE_RX + * @arg @ref LL_I2S_MODE_MASTER_TX + * @arg @ref LL_I2S_MODE_MASTER_RX + */ +__STATIC_INLINE uint32_t LL_I2S_GetTransferMode(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG)); +} + +/** + * @brief Set I2S linear prescaler + * @rmtoll I2SPR I2SDIV LL_I2S_SetPrescalerLinear + * @param SPIx SPI Instance + * @param PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetPrescalerLinear(SPI_TypeDef *SPIx, uint8_t PrescalerLinear) +{ + MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV, PrescalerLinear); +} + +/** + * @brief Get I2S linear prescaler + * @rmtoll I2SPR I2SDIV LL_I2S_GetPrescalerLinear + * @param SPIx SPI Instance + * @retval PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2S_GetPrescalerLinear(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_I2SDIV)); +} + +/** + * @brief Set I2S parity prescaler + * @rmtoll I2SPR ODD LL_I2S_SetPrescalerParity + * @param SPIx SPI Instance + * @param PrescalerParity This parameter can be one of the following values: + * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN + * @arg @ref LL_I2S_PRESCALER_PARITY_ODD + * @retval None + */ +__STATIC_INLINE void LL_I2S_SetPrescalerParity(SPI_TypeDef *SPIx, uint32_t PrescalerParity) +{ + MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_ODD, PrescalerParity << 8U); +} + +/** + * @brief Get I2S parity prescaler + * @rmtoll I2SPR ODD LL_I2S_GetPrescalerParity + * @param SPIx SPI Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN + * @arg @ref LL_I2S_PRESCALER_PARITY_ODD + */ +__STATIC_INLINE uint32_t LL_I2S_GetPrescalerParity(SPI_TypeDef *SPIx) +{ + return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_ODD) >> 8U); +} + +/** + * @brief Enable the master clock output (Pin MCK) + * @rmtoll I2SPR MCKOE LL_I2S_EnableMasterClock + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableMasterClock(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); +} + +/** + * @brief Disable the master clock output (Pin MCK) + * @rmtoll I2SPR MCKOE LL_I2S_DisableMasterClock + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableMasterClock(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); +} + +/** + * @brief Check if the master clock output (Pin MCK) is enabled + * @rmtoll I2SPR MCKOE LL_I2S_IsEnabledMasterClock + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledMasterClock(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE) == (SPI_I2SPR_MCKOE)) ? 1UL : 0UL); +} + +#if defined(SPI_I2SCFGR_ASTRTEN) +/** + * @brief Enable asynchronous start + * @rmtoll I2SCFGR ASTRTEN LL_I2S_EnableAsyncStart + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableAsyncStart(SPI_TypeDef *SPIx) +{ + SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); +} + +/** + * @brief Disable asynchronous start + * @rmtoll I2SCFGR ASTRTEN LL_I2S_DisableAsyncStart + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableAsyncStart(SPI_TypeDef *SPIx) +{ + CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); +} + +/** + * @brief Check if asynchronous start is enabled + * @rmtoll I2SCFGR ASTRTEN LL_I2S_IsEnabledAsyncStart + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledAsyncStart(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN) == (SPI_I2SCFGR_ASTRTEN)) ? 1UL : 0UL); +} +#endif /* SPI_I2SCFGR_ASTRTEN */ + +/** + * @} + */ + +/** @defgroup I2S_LL_EF_FLAG FLAG Management + * @{ + */ + +/** + * @brief Check if Rx buffer is not empty + * @rmtoll SR RXNE LL_I2S_IsActiveFlag_RXNE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsActiveFlag_RXNE(SPIx); +} + +/** + * @brief Check if Tx buffer is empty + * @rmtoll SR TXE LL_I2S_IsActiveFlag_TXE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_TXE(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsActiveFlag_TXE(SPIx); +} + +/** + * @brief Get busy flag + * @rmtoll SR BSY LL_I2S_IsActiveFlag_BSY + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_BSY(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsActiveFlag_BSY(SPIx); +} + +/** + * @brief Get overrun error flag + * @rmtoll SR OVR LL_I2S_IsActiveFlag_OVR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_OVR(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsActiveFlag_OVR(SPIx); +} + +/** + * @brief Get underrun error flag + * @rmtoll SR UDR LL_I2S_IsActiveFlag_UDR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_UDR(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_UDR) == (SPI_SR_UDR)) ? 1UL : 0UL); +} + +/** + * @brief Get frame format error flag + * @rmtoll SR FRE LL_I2S_IsActiveFlag_FRE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_FRE(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsActiveFlag_FRE(SPIx); +} + +/** + * @brief Get channel side flag. + * @note 0: Channel Left has to be transmitted or has been received\n + * 1: Channel Right has to be transmitted or has been received\n + * It has no significance in PCM mode. + * @rmtoll SR CHSIDE LL_I2S_IsActiveFlag_CHSIDE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_CHSIDE(SPI_TypeDef *SPIx) +{ + return ((READ_BIT(SPIx->SR, SPI_SR_CHSIDE) == (SPI_SR_CHSIDE)) ? 1UL : 0UL); +} + +/** + * @brief Clear overrun error flag + * @rmtoll SR OVR LL_I2S_ClearFlag_OVR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_ClearFlag_OVR(SPI_TypeDef *SPIx) +{ + LL_SPI_ClearFlag_OVR(SPIx); +} + +/** + * @brief Clear underrun error flag + * @rmtoll SR UDR LL_I2S_ClearFlag_UDR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_ClearFlag_UDR(SPI_TypeDef *SPIx) +{ + __IO uint32_t tmpreg; + tmpreg = SPIx->SR; + (void)tmpreg; +} + +/** + * @brief Clear frame format error flag + * @rmtoll SR FRE LL_I2S_ClearFlag_FRE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_ClearFlag_FRE(SPI_TypeDef *SPIx) +{ + LL_SPI_ClearFlag_FRE(SPIx); +} + +/** + * @} + */ + +/** @defgroup I2S_LL_EF_IT Interrupt Management + * @{ + */ + +/** + * @brief Enable error IT + * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). + * @rmtoll CR2 ERRIE LL_I2S_EnableIT_ERR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableIT_ERR(SPI_TypeDef *SPIx) +{ + LL_SPI_EnableIT_ERR(SPIx); +} + +/** + * @brief Enable Rx buffer not empty IT + * @rmtoll CR2 RXNEIE LL_I2S_EnableIT_RXNE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableIT_RXNE(SPI_TypeDef *SPIx) +{ + LL_SPI_EnableIT_RXNE(SPIx); +} + +/** + * @brief Enable Tx buffer empty IT + * @rmtoll CR2 TXEIE LL_I2S_EnableIT_TXE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableIT_TXE(SPI_TypeDef *SPIx) +{ + LL_SPI_EnableIT_TXE(SPIx); +} + +/** + * @brief Disable error IT + * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). + * @rmtoll CR2 ERRIE LL_I2S_DisableIT_ERR + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableIT_ERR(SPI_TypeDef *SPIx) +{ + LL_SPI_DisableIT_ERR(SPIx); +} + +/** + * @brief Disable Rx buffer not empty IT + * @rmtoll CR2 RXNEIE LL_I2S_DisableIT_RXNE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableIT_RXNE(SPI_TypeDef *SPIx) +{ + LL_SPI_DisableIT_RXNE(SPIx); +} + +/** + * @brief Disable Tx buffer empty IT + * @rmtoll CR2 TXEIE LL_I2S_DisableIT_TXE + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableIT_TXE(SPI_TypeDef *SPIx) +{ + LL_SPI_DisableIT_TXE(SPIx); +} + +/** + * @brief Check if ERR IT is enabled + * @rmtoll CR2 ERRIE LL_I2S_IsEnabledIT_ERR + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_ERR(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsEnabledIT_ERR(SPIx); +} + +/** + * @brief Check if RXNE IT is enabled + * @rmtoll CR2 RXNEIE LL_I2S_IsEnabledIT_RXNE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsEnabledIT_RXNE(SPIx); +} + +/** + * @brief Check if TXE IT is enabled + * @rmtoll CR2 TXEIE LL_I2S_IsEnabledIT_TXE + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_TXE(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsEnabledIT_TXE(SPIx); +} + +/** + * @} + */ + +/** @defgroup I2S_LL_EF_DMA DMA Management + * @{ + */ + +/** + * @brief Enable DMA Rx + * @rmtoll CR2 RXDMAEN LL_I2S_EnableDMAReq_RX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableDMAReq_RX(SPI_TypeDef *SPIx) +{ + LL_SPI_EnableDMAReq_RX(SPIx); +} + +/** + * @brief Disable DMA Rx + * @rmtoll CR2 RXDMAEN LL_I2S_DisableDMAReq_RX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableDMAReq_RX(SPI_TypeDef *SPIx) +{ + LL_SPI_DisableDMAReq_RX(SPIx); +} + +/** + * @brief Check if DMA Rx is enabled + * @rmtoll CR2 RXDMAEN LL_I2S_IsEnabledDMAReq_RX + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsEnabledDMAReq_RX(SPIx); +} + +/** + * @brief Enable DMA Tx + * @rmtoll CR2 TXDMAEN LL_I2S_EnableDMAReq_TX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_EnableDMAReq_TX(SPI_TypeDef *SPIx) +{ + LL_SPI_EnableDMAReq_TX(SPIx); +} + +/** + * @brief Disable DMA Tx + * @rmtoll CR2 TXDMAEN LL_I2S_DisableDMAReq_TX + * @param SPIx SPI Instance + * @retval None + */ +__STATIC_INLINE void LL_I2S_DisableDMAReq_TX(SPI_TypeDef *SPIx) +{ + LL_SPI_DisableDMAReq_TX(SPIx); +} + +/** + * @brief Check if DMA Tx is enabled + * @rmtoll CR2 TXDMAEN LL_I2S_IsEnabledDMAReq_TX + * @param SPIx SPI Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) +{ + return LL_SPI_IsEnabledDMAReq_TX(SPIx); +} + +/** + * @} + */ + +/** @defgroup I2S_LL_EF_DATA DATA Management + * @{ + */ + +/** + * @brief Read 16-Bits in data register + * @rmtoll DR DR LL_I2S_ReceiveData16 + * @param SPIx SPI Instance + * @retval RxData Value between Min_Data=0x0000 and Max_Data=0xFFFF + */ +__STATIC_INLINE uint16_t LL_I2S_ReceiveData16(SPI_TypeDef *SPIx) +{ + return LL_SPI_ReceiveData16(SPIx); +} + +/** + * @brief Write 16-Bits in data register + * @rmtoll DR DR LL_I2S_TransmitData16 + * @param SPIx SPI Instance + * @param TxData Value between Min_Data=0x0000 and Max_Data=0xFFFF + * @retval None + */ +__STATIC_INLINE void LL_I2S_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) +{ + LL_SPI_TransmitData16(SPIx, TxData); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2S_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx); +ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct); +void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct); +void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity); +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) +ErrorStatus LL_I2S_InitFullDuplex(SPI_TypeDef *I2Sxext, LL_I2S_InitTypeDef *I2S_InitStruct); +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F4xx_LL_SPI_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h index 84ea5c4..48bcc1a 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h @@ -1,1711 +1,1711 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_system.h - * @author MCD Application Team - * @brief Header file of SYSTEM LL module. - * - ****************************************************************************** - * @attention - * - *Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL SYSTEM driver contains a set of generic APIs that can be - used by user: - (+) Some of the FLASH features need to be handled in the SYSTEM file. - (+) Access to DBGCMU registers - (+) Access to SYSCFG registers - - @endverbatim - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_SYSTEM_H -#define __STM32F4xx_LL_SYSTEM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) - -/** @defgroup SYSTEM_LL SYSTEM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Private_Constants SYSTEM Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Constants SYSTEM Exported Constants - * @{ - */ - -/** @defgroup SYSTEM_LL_EC_REMAP SYSCFG REMAP -* @{ -*/ -#define LL_SYSCFG_REMAP_FLASH (uint32_t)0x00000000 /*!< Main Flash memory mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SYSTEMFLASH SYSCFG_MEMRMP_MEM_MODE_0 /*!< System Flash memory mapped at 0x00000000 */ -#if defined(FSMC_Bank1) -#define LL_SYSCFG_REMAP_FSMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FSMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_SYSCFG_REMAP_FMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SDRAM SYSCFG_MEMRMP_MEM_MODE_2 /*!< FMC/SDRAM mapped at 0x00000000 */ -#endif /* FMC_Bank1 */ -#define LL_SYSCFG_REMAP_SRAM (SYSCFG_MEMRMP_MEM_MODE_1 | SYSCFG_MEMRMP_MEM_MODE_0) /*!< SRAM1 mapped at 0x00000000 */ - -/** - * @} - */ - -#if defined(SYSCFG_PMC_MII_RMII_SEL) - /** @defgroup SYSTEM_LL_EC_PMC SYSCFG PMC -* @{ -*/ -#define LL_SYSCFG_PMC_ETHMII (uint32_t)0x00000000 /*!< ETH Media MII interface */ -#define LL_SYSCFG_PMC_ETHRMII (uint32_t)SYSCFG_PMC_MII_RMII_SEL /*!< ETH Media RMII interface */ - -/** - * @} - */ -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** @defgroup SYSTEM_LL_EC_BANKMODE SYSCFG BANK MODE - * @{ - */ -#define LL_SYSCFG_BANKMODE_BANK1 (uint32_t)0x00000000 /*!< Flash Bank 1 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000 (TCM) - and Flash Bank 2 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000 (TCM)*/ -#define LL_SYSCFG_BANKMODE_BANK2 SYSCFG_MEMRMP_UFB_MODE /*!< Flash Bank 2 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000(TCM) - and Flash Bank 1 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000(TCM) */ -/** - * @} - */ -#endif /* SYSCFG_MEMRMP_UFB_MODE */ -/** @defgroup SYSTEM_LL_EC_I2C_FASTMODEPLUS SYSCFG I2C FASTMODEPLUS - * @{ - */ -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -#define LL_SYSCFG_I2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C_SCL pin */ -#define LL_SYSCFG_I2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C_SDA pin*/ -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_PORT SYSCFG EXTI PORT - * @{ - */ -#define LL_SYSCFG_EXTI_PORTA (uint32_t)0 /*!< EXTI PORT A */ -#define LL_SYSCFG_EXTI_PORTB (uint32_t)1 /*!< EXTI PORT B */ -#define LL_SYSCFG_EXTI_PORTC (uint32_t)2 /*!< EXTI PORT C */ -#define LL_SYSCFG_EXTI_PORTD (uint32_t)3 /*!< EXTI PORT D */ -#define LL_SYSCFG_EXTI_PORTE (uint32_t)4 /*!< EXTI PORT E */ -#if defined(GPIOF) -#define LL_SYSCFG_EXTI_PORTF (uint32_t)5 /*!< EXTI PORT F */ -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_SYSCFG_EXTI_PORTG (uint32_t)6 /*!< EXTI PORT G */ -#endif /* GPIOG */ -#define LL_SYSCFG_EXTI_PORTH (uint32_t)7 /*!< EXTI PORT H */ -#if defined(GPIOI) -#define LL_SYSCFG_EXTI_PORTI (uint32_t)8 /*!< EXTI PORT I */ -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_SYSCFG_EXTI_PORTJ (uint32_t)9 /*!< EXTI PORT J */ -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_SYSCFG_EXTI_PORTK (uint32_t)10 /*!< EXTI PORT k */ -#endif /* GPIOK */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_LINE SYSCFG EXTI LINE - * @{ - */ -#define LL_SYSCFG_EXTI_LINE0 (uint32_t)(0x000FU << 16 | 0) /*!< EXTI_POSITION_0 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE1 (uint32_t)(0x00F0U << 16 | 0) /*!< EXTI_POSITION_4 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE2 (uint32_t)(0x0F00U << 16 | 0) /*!< EXTI_POSITION_8 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE3 (uint32_t)(0xF000U << 16 | 0) /*!< EXTI_POSITION_12 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE4 (uint32_t)(0x000FU << 16 | 1) /*!< EXTI_POSITION_0 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE5 (uint32_t)(0x00F0U << 16 | 1) /*!< EXTI_POSITION_4 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE6 (uint32_t)(0x0F00U << 16 | 1) /*!< EXTI_POSITION_8 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE7 (uint32_t)(0xF000U << 16 | 1) /*!< EXTI_POSITION_12 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE8 (uint32_t)(0x000FU << 16 | 2) /*!< EXTI_POSITION_0 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE9 (uint32_t)(0x00F0U << 16 | 2) /*!< EXTI_POSITION_4 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE10 (uint32_t)(0x0F00U << 16 | 2) /*!< EXTI_POSITION_8 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE11 (uint32_t)(0xF000U << 16 | 2) /*!< EXTI_POSITION_12 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE12 (uint32_t)(0x000FU << 16 | 3) /*!< EXTI_POSITION_0 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE13 (uint32_t)(0x00F0U << 16 | 3) /*!< EXTI_POSITION_4 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE14 (uint32_t)(0x0F00U << 16 | 3) /*!< EXTI_POSITION_8 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE15 (uint32_t)(0xF000U << 16 | 3) /*!< EXTI_POSITION_12 | EXTICR[3] */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_TIMBREAK SYSCFG TIMER BREAK - * @{ - */ -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -#define LL_SYSCFG_TIMBREAK_LOCKUP SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP output of CortexM4 - with Break Input of TIM1/8 */ -#define LL_SYSCFG_TIMBREAK_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection with TIM1/8 Break Input - and also the PVDE and PLS bits of the Power Control Interface */ -#endif /* SYSCFG_CFGR2_CLL */ -/** - * @} - */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** @defgroup SYSTEM_LL_DFSDM_BitStream_ClockSource SYSCFG MCHDLY BCKKSEL - * @{ - */ -#define LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 (uint32_t)0x00000000 -#define LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_BSCKSEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_MCHDLYEN SYSCFG MCHDLY MCHDLYEN - * @{ - */ -#define LL_SYSCFG_DFSDM1_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY1EN -#define LL_SYSCFG_DFSDM2_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY2EN -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn0_Source SYSCFG MCHDLY DFSDMD0SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn0 SYSCFG_MCHDLYCR_DFSDM1D0SEL -#define LL_SYSCFG_DFSDM2_DataIn0 SYSCFG_MCHDLYCR_DFSDM2D0SEL - -#define LL_SYSCFG_DFSDM1_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D0SEL) -#define LL_SYSCFG_DFSDM2_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D0SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn2_Source SYSCFG MCHDLY DFSDMD2SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn2 SYSCFG_MCHDLYCR_DFSDM1D2SEL -#define LL_SYSCFG_DFSDM2_DataIn2 SYSCFG_MCHDLYCR_DFSDM2D2SEL - -#define LL_SYSCFG_DFSDM1_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D2SEL) -#define LL_SYSCFG_DFSDM2_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D2SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK02SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK13SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKIN_SourceSelection SYSCFG MCHDLY DFSDMCFG - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM1CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL -/** - * @} - */ - -/** @defgroup SYSTEM_LL_DFSDM2_DataIn4_SourceSelection SYSCFG MCHDLY DFSDM2D4SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn4_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn4_DM SYSCFG_MCHDLYCR_DFSDM2D4SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_DataIn6_SourceSelection SYSCFG MCHDLY DFSDM2D6SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn6_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn6_DM SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC4_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK04SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC3_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK15SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK26SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK37SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKIN_SourceSelection SYSCFG MCHDLY DFSDM2CFG - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM2CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL -/** - * @} - */ -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ - -/** @defgroup SYSTEM_LL_EC_TRACE DBGMCU TRACE Pin Assignment - * @{ - */ -#define LL_DBGMCU_TRACE_NONE 0x00000000U /*!< TRACE pins not assigned (default state) */ -#define LL_DBGMCU_TRACE_ASYNCH DBGMCU_CR_TRACE_IOEN /*!< TRACE pin assignment for Asynchronous Mode */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE1 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_0) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 1 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE2 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_1) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 2 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE4 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 4 */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB1_GRP1_STOP_IP DBGMCU APB1 GRP1 STOP IP - * @{ - */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM2_STOP DBGMCU_APB1_FZ_DBG_TIM2_STOP /*!< TIM2 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM3_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM3_STOP DBGMCU_APB1_FZ_DBG_TIM3_STOP /*!< TIM3 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM3_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM4_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM4_STOP DBGMCU_APB1_FZ_DBG_TIM4_STOP /*!< TIM4 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM4_STOP */ -#define LL_DBGMCU_APB1_GRP1_TIM5_STOP DBGMCU_APB1_FZ_DBG_TIM5_STOP /*!< TIM5 counter stopped when core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM6_STOP DBGMCU_APB1_FZ_DBG_TIM6_STOP /*!< TIM6 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM6_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM7_STOP DBGMCU_APB1_FZ_DBG_TIM7_STOP /*!< TIM7 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM7_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM12_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM12_STOP DBGMCU_APB1_FZ_DBG_TIM12_STOP /*!< TIM12 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM12_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM13_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM13_STOP DBGMCU_APB1_FZ_DBG_TIM13_STOP /*!< TIM13 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM13_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM14_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM14_STOP DBGMCU_APB1_FZ_DBG_TIM14_STOP /*!< TIM14 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM14_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_LPTIM_STOP) -#define LL_DBGMCU_APB1_GRP1_LPTIM_STOP DBGMCU_APB1_FZ_DBG_LPTIM_STOP /*!< LPTIM counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_LPTIM_STOP */ -#define LL_DBGMCU_APB1_GRP1_RTC_STOP DBGMCU_APB1_FZ_DBG_RTC_STOP /*!< RTC counter stopped when core is halted */ -#define LL_DBGMCU_APB1_GRP1_WWDG_STOP DBGMCU_APB1_FZ_DBG_WWDG_STOP /*!< Debug Window Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_IWDG_STOP DBGMCU_APB1_FZ_DBG_IWDG_STOP /*!< Debug Independent Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C1_STOP DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT /*!< I2C1 SMBUS timeout mode stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C2_STOP DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT /*!< I2C2 SMBUS timeout mode stopped when Core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C3_STOP DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT /*!< I2C3 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C4_STOP DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT /*!< I2C4 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN1_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN1_STOP DBGMCU_APB1_FZ_DBG_CAN1_STOP /*!< CAN1 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN1_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN2_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN2_STOP DBGMCU_APB1_FZ_DBG_CAN2_STOP /*!< CAN2 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN3_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN3_STOP DBGMCU_APB1_FZ_DBG_CAN3_STOP /*!< CAN3 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN3_STOP */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB2_GRP1_STOP_IP DBGMCU APB2 GRP1 STOP IP - * @{ - */ -#define LL_DBGMCU_APB2_GRP1_TIM1_STOP DBGMCU_APB2_FZ_DBG_TIM1_STOP /*!< TIM1 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM8_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM8_STOP DBGMCU_APB2_FZ_DBG_TIM8_STOP /*!< TIM8 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM8_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM9_STOP DBGMCU_APB2_FZ_DBG_TIM9_STOP /*!< TIM9 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM10_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM10_STOP DBGMCU_APB2_FZ_DBG_TIM10_STOP /*!< TIM10 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM10_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM11_STOP DBGMCU_APB2_FZ_DBG_TIM11_STOP /*!< TIM11 counter stopped when core is halted */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_LATENCY FLASH LATENCY - * @{ - */ -#define LL_FLASH_LATENCY_0 FLASH_ACR_LATENCY_0WS /*!< FLASH Zero wait state */ -#define LL_FLASH_LATENCY_1 FLASH_ACR_LATENCY_1WS /*!< FLASH One wait state */ -#define LL_FLASH_LATENCY_2 FLASH_ACR_LATENCY_2WS /*!< FLASH Two wait states */ -#define LL_FLASH_LATENCY_3 FLASH_ACR_LATENCY_3WS /*!< FLASH Three wait states */ -#define LL_FLASH_LATENCY_4 FLASH_ACR_LATENCY_4WS /*!< FLASH Four wait states */ -#define LL_FLASH_LATENCY_5 FLASH_ACR_LATENCY_5WS /*!< FLASH five wait state */ -#define LL_FLASH_LATENCY_6 FLASH_ACR_LATENCY_6WS /*!< FLASH six wait state */ -#define LL_FLASH_LATENCY_7 FLASH_ACR_LATENCY_7WS /*!< FLASH seven wait states */ -#define LL_FLASH_LATENCY_8 FLASH_ACR_LATENCY_8WS /*!< FLASH eight wait states */ -#define LL_FLASH_LATENCY_9 FLASH_ACR_LATENCY_9WS /*!< FLASH nine wait states */ -#define LL_FLASH_LATENCY_10 FLASH_ACR_LATENCY_10WS /*!< FLASH ten wait states */ -#define LL_FLASH_LATENCY_11 FLASH_ACR_LATENCY_11WS /*!< FLASH eleven wait states */ -#define LL_FLASH_LATENCY_12 FLASH_ACR_LATENCY_12WS /*!< FLASH twelve wait states */ -#define LL_FLASH_LATENCY_13 FLASH_ACR_LATENCY_13WS /*!< FLASH thirteen wait states */ -#define LL_FLASH_LATENCY_14 FLASH_ACR_LATENCY_14WS /*!< FLASH fourteen wait states */ -#define LL_FLASH_LATENCY_15 FLASH_ACR_LATENCY_15WS /*!< FLASH fifteen wait states */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Functions SYSTEM Exported Functions - * @{ - */ - -/** @defgroup SYSTEM_LL_EF_SYSCFG SYSCFG - * @{ - */ -/** - * @brief Set memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_SetRemapMemory - * @param Memory This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetRemapMemory(uint32_t Memory) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE, Memory); -} - -/** - * @brief Get memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_GetRemapMemory - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetRemapMemory(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE)); -} - -#if defined(SYSCFG_MEMRMP_SWP_FMC) -/** - * @brief Enables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_EnableFMCMemorySwapping - * @note SDRAM is accessible at 0x60000000 and NOR/RAM - * is accessible at 0xC0000000 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFMCMemorySwapping(void) -{ - SET_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC_0); -} - -/** - * @brief Disables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_DisableFMCMemorySwapping - * @note SDRAM is accessible at 0xC0000000 (default mapping) - * and NOR/RAM is accessible at 0x60000000 (default mapping) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFMCMemorySwapping(void) -{ - CLEAR_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC); -} - -#endif /* SYSCFG_MEMRMP_SWP_FMC */ -/** - * @brief Enables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_EnableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableCompensationCell(void) -{ - SET_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Disables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_DisableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableCompensationCell(void) -{ - CLEAR_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Get Compensation Cell ready Flag - * @rmtoll SYSCFG_CMPCR READY LL_SYSCFG_IsActiveFlag_CMPCR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CMPCR(void) -{ - return (READ_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_READY) == (SYSCFG_CMPCR_READY)); -} - -#if defined(SYSCFG_PMC_MII_RMII_SEL) -/** - * @brief Select Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_SetPHYInterface - * @param Interface This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetPHYInterface(uint32_t Interface) -{ - MODIFY_REG(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL, Interface); -} - -/** - * @brief Get Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_GetPHYInterface - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetPHYInterface(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL)); -} -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** - * @brief Select Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_SetFlashBankMode - * @param Bank This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetFlashBankMode(uint32_t Bank) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE, Bank); -} - -/** - * @brief Get Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_GetFlashBankMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetFlashBankMode(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE)); -} -#endif /* SYSCFG_MEMRMP_UFB_MODE */ - -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -/** - * @brief Enable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_EnableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_EnableFastModePlus - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFastModePlus(uint32_t ConfigFastModePlus) -{ - SET_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} - -/** - * @brief Disable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_DisableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_DisableFastModePlus\n - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFastModePlus(uint32_t ConfigFastModePlus) -{ - CLEAR_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ - -/** - * @brief Configure source input for the EXTI external interrupt. - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_SetEXTISource - * @param Port This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * - * (*) value not defined in all devices - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetEXTISource(uint32_t Port, uint32_t Line) -{ - MODIFY_REG(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16), Port << POSITION_VAL((Line >> 16))); -} - -/** - * @brief Get the configured defined for specific EXTI Line - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_GetEXTISource - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * (*) value not defined in all devices - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetEXTISource(uint32_t Line) -{ - return (uint32_t)(READ_BIT(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16)) >> POSITION_VAL(Line >> 16)); -} - -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -/** - * @brief Set connections to TIM1/8 break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @param Break This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetTIMBreakInputs(uint32_t Break) -{ - MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK, Break); -} - -/** - * @brief Get connections to TIM1/8 Break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetTIMBreakInputs(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK)); -} -#endif /* SYSCFG_CFGR2_LOCKUP_LOCK */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Select the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL, ClockSource); -} -/** - * @brief Get the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL)); -} -/** - * @brief Enables the DFSDM1 or DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLYEN LL_SYSCFG_DFSDM_EnableDelayClock - * @param MCHDLY This parameter can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_EnableDelayClock(uint32_t MCHDLY) -{ - SET_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Disables the DFSDM1 or the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY1EN LL_SYSCFG_DFSDM1_DisableDelayClock - * @param MCHDLY This parameter can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_DisableDelayClock(uint32_t MCHDLY) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_GetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn0Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_GetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn2Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK02SEL LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK13SEL LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL)); -} - -/** - * @brief Select the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG)); -} - -/** - * @brief Select the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL)); -} - -/** - * @brief Enables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_EnableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_EnableDelayClock(void) -{ - SET_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} - -/** - * @brief Disables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_DisableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_DisableDelayClock(void) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} -/** - * @brief Select the source for DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_GetDataIn0Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn0Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_GetDataIn2Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn2Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_SetDataIn4Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn4Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn4. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_GetDataIn4Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn4Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn6 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_SetDataIn6Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn6Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn6. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_GetDataIn6Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn6Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC3 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK15SEL LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK26SEL LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL)); -} - -/** - * @brief Select the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG)); -} - -/** - * @brief Select the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL)); -} - -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ - - -/** @defgroup SYSTEM_LL_EF_DBGMCU DBGMCU - * @{ - */ - -/** - * @brief Return the device identifier - * @note For STM32F405/407xx and STM32F415/417xx devices, the device ID is 0x413 - * @note For STM32F42xxx and STM32F43xxx devices, the device ID is 0x419 - * @note For STM32F401xx devices, the device ID is 0x423 - * @note For STM32F401xx devices, the device ID is 0x433 - * @note For STM32F411xx devices, the device ID is 0x431 - * @note For STM32F410xx devices, the device ID is 0x458 - * @note For STM32F412xx devices, the device ID is 0x441 - * @note For STM32F413xx and STM32423xx devices, the device ID is 0x463 - * @note For STM32F446xx devices, the device ID is 0x421 - * @note For STM32F469xx and STM32F479xx devices, the device ID is 0x434 - * @rmtoll DBGMCU_IDCODE DEV_ID LL_DBGMCU_GetDeviceID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetDeviceID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_DEV_ID)); -} - -/** - * @brief Return the device revision identifier - * @note This field indicates the revision of the device. - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001, rev1 -> 0x1003, rev2 ->0x1007, revY -> 0x100F for STM32F405/407xx and STM32F415/417xx devices - For example, it is read as RevA -> 0x1000, Cat 2 revY -> 0x1003, rev1 -> 0x1007, rev3 ->0x2001 for STM32F42xxx and STM32F43xxx devices - For example, it is read as RevZ -> 0x1000, Cat 2 revA -> 0x1001 for STM32F401xB/C devices - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001 for STM32F401xD/E devices - For example, it is read as RevA -> 0x1000 for STM32F411xx,STM32F413/423xx,STM32F469/423xx, STM32F446xx and STM32F410xx devices - For example, it is read as RevZ -> 0x1001, Cat 2 revB -> 0x2000, revC -> 0x3000 for STM32F412xx devices - * @rmtoll DBGMCU_IDCODE REV_ID LL_DBGMCU_GetRevisionID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetRevisionID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_REV_ID) >> DBGMCU_IDCODE_REV_ID_Pos); -} - -/** - * @brief Enable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_EnableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGSleepMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Disable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_DisableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGSleepMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Enable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_EnableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStopMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Disable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_DisableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStopMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Enable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_EnableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStandbyMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Disable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_DisableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStandbyMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Set Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_SetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_SetTracePinAssignment - * @param PinAssignment This parameter can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_SetTracePinAssignment(uint32_t PinAssignment) -{ - MODIFY_REG(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE, PinAssignment); -} - -/** - * @brief Get Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_GetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_GetTracePinAssignment - * @retval Returned value can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetTracePinAssignment(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE)); -} - -/** - * @brief Freeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Unfreeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Freeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB2FZ, Periphs); -} - -/** - * @brief Unfreeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB2FZ, Periphs); -} -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EF_FLASH FLASH - * @{ - */ - -/** - * @brief Set FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_SetLatency - * @param Latency This parameter can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - * @retval None - */ -__STATIC_INLINE void LL_FLASH_SetLatency(uint32_t Latency) -{ - MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, Latency); -} - -/** - * @brief Get FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_GetLatency - * @retval Returned value can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - */ -__STATIC_INLINE uint32_t LL_FLASH_GetLatency(void) -{ - return (uint32_t)(READ_BIT(FLASH->ACR, FLASH_ACR_LATENCY)); -} - -/** - * @brief Enable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_EnablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnablePrefetch(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Disable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_DisablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisablePrefetch(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Check if Prefetch buffer is enabled - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_IsPrefetchEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FLASH_IsPrefetchEnabled(void) -{ - return (READ_BIT(FLASH->ACR, FLASH_ACR_PRFTEN) == (FLASH_ACR_PRFTEN)); -} - -/** - * @brief Enable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_EnableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Disable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_DisableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Enable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_EnableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Disable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_DisableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Enable Instruction cache reset - * @note bit can be written only when the instruction cache is disabled - * @rmtoll FLASH_ACR ICRST LL_FLASH_EnableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Disable Instruction cache reset - * @rmtoll FLASH_ACR ICRST LL_FLASH_DisableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Enable Data cache reset - * @note bit can be written only when the data cache is disabled - * @rmtoll FLASH_ACR DCRST LL_FLASH_EnableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - -/** - * @brief Disable Data cache reset - * @rmtoll FLASH_ACR DCRST LL_FLASH_DisableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_SYSTEM_H */ - - +/** + ****************************************************************************** + * @file stm32f4xx_ll_system.h + * @author MCD Application Team + * @brief Header file of SYSTEM LL module. + * + ****************************************************************************** + * @attention + * + *Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The LL SYSTEM driver contains a set of generic APIs that can be + used by user: + (+) Some of the FLASH features need to be handled in the SYSTEM file. + (+) Access to DBGCMU registers + (+) Access to SYSCFG registers + + @endverbatim + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_SYSTEM_H +#define __STM32F4xx_LL_SYSTEM_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) + +/** @defgroup SYSTEM_LL SYSTEM + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup SYSTEM_LL_Private_Constants SYSTEM Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup SYSTEM_LL_Exported_Constants SYSTEM Exported Constants + * @{ + */ + +/** @defgroup SYSTEM_LL_EC_REMAP SYSCFG REMAP +* @{ +*/ +#define LL_SYSCFG_REMAP_FLASH (uint32_t)0x00000000 /*!< Main Flash memory mapped at 0x00000000 */ +#define LL_SYSCFG_REMAP_SYSTEMFLASH SYSCFG_MEMRMP_MEM_MODE_0 /*!< System Flash memory mapped at 0x00000000 */ +#if defined(FSMC_Bank1) +#define LL_SYSCFG_REMAP_FSMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FSMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ +#endif /* FSMC_Bank1 */ +#if defined(FMC_Bank1) +#define LL_SYSCFG_REMAP_FMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ +#define LL_SYSCFG_REMAP_SDRAM SYSCFG_MEMRMP_MEM_MODE_2 /*!< FMC/SDRAM mapped at 0x00000000 */ +#endif /* FMC_Bank1 */ +#define LL_SYSCFG_REMAP_SRAM (SYSCFG_MEMRMP_MEM_MODE_1 | SYSCFG_MEMRMP_MEM_MODE_0) /*!< SRAM1 mapped at 0x00000000 */ + +/** + * @} + */ + +#if defined(SYSCFG_PMC_MII_RMII_SEL) + /** @defgroup SYSTEM_LL_EC_PMC SYSCFG PMC +* @{ +*/ +#define LL_SYSCFG_PMC_ETHMII (uint32_t)0x00000000 /*!< ETH Media MII interface */ +#define LL_SYSCFG_PMC_ETHRMII (uint32_t)SYSCFG_PMC_MII_RMII_SEL /*!< ETH Media RMII interface */ + +/** + * @} + */ +#endif /* SYSCFG_PMC_MII_RMII_SEL */ + + + +#if defined(SYSCFG_MEMRMP_UFB_MODE) +/** @defgroup SYSTEM_LL_EC_BANKMODE SYSCFG BANK MODE + * @{ + */ +#define LL_SYSCFG_BANKMODE_BANK1 (uint32_t)0x00000000 /*!< Flash Bank 1 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000 (TCM) + and Flash Bank 2 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000 (TCM)*/ +#define LL_SYSCFG_BANKMODE_BANK2 SYSCFG_MEMRMP_UFB_MODE /*!< Flash Bank 2 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000(TCM) + and Flash Bank 1 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000(TCM) */ +/** + * @} + */ +#endif /* SYSCFG_MEMRMP_UFB_MODE */ +/** @defgroup SYSTEM_LL_EC_I2C_FASTMODEPLUS SYSCFG I2C FASTMODEPLUS + * @{ + */ +#if defined(SYSCFG_CFGR_FMPI2C1_SCL) +#define LL_SYSCFG_I2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C_SCL pin */ +#define LL_SYSCFG_I2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C_SDA pin*/ +#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_EXTI_PORT SYSCFG EXTI PORT + * @{ + */ +#define LL_SYSCFG_EXTI_PORTA (uint32_t)0 /*!< EXTI PORT A */ +#define LL_SYSCFG_EXTI_PORTB (uint32_t)1 /*!< EXTI PORT B */ +#define LL_SYSCFG_EXTI_PORTC (uint32_t)2 /*!< EXTI PORT C */ +#define LL_SYSCFG_EXTI_PORTD (uint32_t)3 /*!< EXTI PORT D */ +#define LL_SYSCFG_EXTI_PORTE (uint32_t)4 /*!< EXTI PORT E */ +#if defined(GPIOF) +#define LL_SYSCFG_EXTI_PORTF (uint32_t)5 /*!< EXTI PORT F */ +#endif /* GPIOF */ +#if defined(GPIOG) +#define LL_SYSCFG_EXTI_PORTG (uint32_t)6 /*!< EXTI PORT G */ +#endif /* GPIOG */ +#define LL_SYSCFG_EXTI_PORTH (uint32_t)7 /*!< EXTI PORT H */ +#if defined(GPIOI) +#define LL_SYSCFG_EXTI_PORTI (uint32_t)8 /*!< EXTI PORT I */ +#endif /* GPIOI */ +#if defined(GPIOJ) +#define LL_SYSCFG_EXTI_PORTJ (uint32_t)9 /*!< EXTI PORT J */ +#endif /* GPIOJ */ +#if defined(GPIOK) +#define LL_SYSCFG_EXTI_PORTK (uint32_t)10 /*!< EXTI PORT k */ +#endif /* GPIOK */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_EXTI_LINE SYSCFG EXTI LINE + * @{ + */ +#define LL_SYSCFG_EXTI_LINE0 (uint32_t)(0x000FU << 16 | 0) /*!< EXTI_POSITION_0 | EXTICR[0] */ +#define LL_SYSCFG_EXTI_LINE1 (uint32_t)(0x00F0U << 16 | 0) /*!< EXTI_POSITION_4 | EXTICR[0] */ +#define LL_SYSCFG_EXTI_LINE2 (uint32_t)(0x0F00U << 16 | 0) /*!< EXTI_POSITION_8 | EXTICR[0] */ +#define LL_SYSCFG_EXTI_LINE3 (uint32_t)(0xF000U << 16 | 0) /*!< EXTI_POSITION_12 | EXTICR[0] */ +#define LL_SYSCFG_EXTI_LINE4 (uint32_t)(0x000FU << 16 | 1) /*!< EXTI_POSITION_0 | EXTICR[1] */ +#define LL_SYSCFG_EXTI_LINE5 (uint32_t)(0x00F0U << 16 | 1) /*!< EXTI_POSITION_4 | EXTICR[1] */ +#define LL_SYSCFG_EXTI_LINE6 (uint32_t)(0x0F00U << 16 | 1) /*!< EXTI_POSITION_8 | EXTICR[1] */ +#define LL_SYSCFG_EXTI_LINE7 (uint32_t)(0xF000U << 16 | 1) /*!< EXTI_POSITION_12 | EXTICR[1] */ +#define LL_SYSCFG_EXTI_LINE8 (uint32_t)(0x000FU << 16 | 2) /*!< EXTI_POSITION_0 | EXTICR[2] */ +#define LL_SYSCFG_EXTI_LINE9 (uint32_t)(0x00F0U << 16 | 2) /*!< EXTI_POSITION_4 | EXTICR[2] */ +#define LL_SYSCFG_EXTI_LINE10 (uint32_t)(0x0F00U << 16 | 2) /*!< EXTI_POSITION_8 | EXTICR[2] */ +#define LL_SYSCFG_EXTI_LINE11 (uint32_t)(0xF000U << 16 | 2) /*!< EXTI_POSITION_12 | EXTICR[2] */ +#define LL_SYSCFG_EXTI_LINE12 (uint32_t)(0x000FU << 16 | 3) /*!< EXTI_POSITION_0 | EXTICR[3] */ +#define LL_SYSCFG_EXTI_LINE13 (uint32_t)(0x00F0U << 16 | 3) /*!< EXTI_POSITION_4 | EXTICR[3] */ +#define LL_SYSCFG_EXTI_LINE14 (uint32_t)(0x0F00U << 16 | 3) /*!< EXTI_POSITION_8 | EXTICR[3] */ +#define LL_SYSCFG_EXTI_LINE15 (uint32_t)(0xF000U << 16 | 3) /*!< EXTI_POSITION_12 | EXTICR[3] */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_TIMBREAK SYSCFG TIMER BREAK + * @{ + */ +#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) +#define LL_SYSCFG_TIMBREAK_LOCKUP SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP output of CortexM4 + with Break Input of TIM1/8 */ +#define LL_SYSCFG_TIMBREAK_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection with TIM1/8 Break Input + and also the PVDE and PLS bits of the Power Control Interface */ +#endif /* SYSCFG_CFGR2_CLL */ +/** + * @} + */ + +#if defined(SYSCFG_MCHDLYCR_BSCKSEL) +/** @defgroup SYSTEM_LL_DFSDM_BitStream_ClockSource SYSCFG MCHDLY BCKKSEL + * @{ + */ +#define LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 (uint32_t)0x00000000 +#define LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_BSCKSEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM_MCHDLYEN SYSCFG MCHDLY MCHDLYEN + * @{ + */ +#define LL_SYSCFG_DFSDM1_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY1EN +#define LL_SYSCFG_DFSDM2_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY2EN +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM_DataIn0_Source SYSCFG MCHDLY DFSDMD0SEL + * @{ + */ +#define LL_SYSCFG_DFSDM1_DataIn0 SYSCFG_MCHDLYCR_DFSDM1D0SEL +#define LL_SYSCFG_DFSDM2_DataIn0 SYSCFG_MCHDLYCR_DFSDM2D0SEL + +#define LL_SYSCFG_DFSDM1_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | 0x00000000) +#define LL_SYSCFG_DFSDM1_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D0SEL) +#define LL_SYSCFG_DFSDM2_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | 0x00000000) +#define LL_SYSCFG_DFSDM2_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D0SEL) +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM_DataIn2_Source SYSCFG MCHDLY DFSDMD2SEL + * @{ + */ +#define LL_SYSCFG_DFSDM1_DataIn2 SYSCFG_MCHDLYCR_DFSDM1D2SEL +#define LL_SYSCFG_DFSDM2_DataIn2 SYSCFG_MCHDLYCR_DFSDM2D2SEL + +#define LL_SYSCFG_DFSDM1_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | 0x00000000) +#define LL_SYSCFG_DFSDM1_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D2SEL) +#define LL_SYSCFG_DFSDM2_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | 0x00000000) +#define LL_SYSCFG_DFSDM2_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D2SEL) +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK02SEL + * @{ + */ +#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK13SEL + * @{ + */ +#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM1_CLKIN_SourceSelection SYSCFG MCHDLY DFSDMCFG + * @{ + */ +#define LL_SYSCFG_DFSDM1_CKIN_PAD (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM1_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM1CKOSEL + * @{ + */ +#define LL_SYSCFG_DFSDM1_CKOUT (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL +/** + * @} + */ + +/** @defgroup SYSTEM_LL_DFSDM2_DataIn4_SourceSelection SYSCFG MCHDLY DFSDM2D4SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_DataIn4_PAD (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_DataIn4_DM SYSCFG_MCHDLYCR_DFSDM2D4SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_DataIn6_SourceSelection SYSCFG MCHDLY DFSDM2D6SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_DataIn6_PAD (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_DataIn6_DM SYSCFG_MCHDLYCR_DFSDM2D6SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC4_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK04SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC3_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK15SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK26SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK37SEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_CLKIN_SourceSelection SYSCFG MCHDLY DFSDM2CFG + * @{ + */ +#define LL_SYSCFG_DFSDM2_CKIN_PAD (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG +/** + * @} + */ +/** @defgroup SYSTEM_LL_DFSDM2_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM2CKOSEL + * @{ + */ +#define LL_SYSCFG_DFSDM2_CKOUT (uint32_t)0x00000000 +#define LL_SYSCFG_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL +/** + * @} + */ +#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ + +/** @defgroup SYSTEM_LL_EC_TRACE DBGMCU TRACE Pin Assignment + * @{ + */ +#define LL_DBGMCU_TRACE_NONE 0x00000000U /*!< TRACE pins not assigned (default state) */ +#define LL_DBGMCU_TRACE_ASYNCH DBGMCU_CR_TRACE_IOEN /*!< TRACE pin assignment for Asynchronous Mode */ +#define LL_DBGMCU_TRACE_SYNCH_SIZE1 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_0) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 1 */ +#define LL_DBGMCU_TRACE_SYNCH_SIZE2 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_1) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 2 */ +#define LL_DBGMCU_TRACE_SYNCH_SIZE4 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 4 */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_APB1_GRP1_STOP_IP DBGMCU APB1 GRP1 STOP IP + * @{ + */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM2_STOP DBGMCU_APB1_FZ_DBG_TIM2_STOP /*!< TIM2 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM2_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM3_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM3_STOP DBGMCU_APB1_FZ_DBG_TIM3_STOP /*!< TIM3 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM3_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM4_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM4_STOP DBGMCU_APB1_FZ_DBG_TIM4_STOP /*!< TIM4 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM4_STOP */ +#define LL_DBGMCU_APB1_GRP1_TIM5_STOP DBGMCU_APB1_FZ_DBG_TIM5_STOP /*!< TIM5 counter stopped when core is halted */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM6_STOP DBGMCU_APB1_FZ_DBG_TIM6_STOP /*!< TIM6 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM6_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM7_STOP DBGMCU_APB1_FZ_DBG_TIM7_STOP /*!< TIM7 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM7_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM12_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM12_STOP DBGMCU_APB1_FZ_DBG_TIM12_STOP /*!< TIM12 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM12_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM13_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM13_STOP DBGMCU_APB1_FZ_DBG_TIM13_STOP /*!< TIM13 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM13_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_TIM14_STOP) +#define LL_DBGMCU_APB1_GRP1_TIM14_STOP DBGMCU_APB1_FZ_DBG_TIM14_STOP /*!< TIM14 counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_TIM14_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_LPTIM_STOP) +#define LL_DBGMCU_APB1_GRP1_LPTIM_STOP DBGMCU_APB1_FZ_DBG_LPTIM_STOP /*!< LPTIM counter stopped when core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_LPTIM_STOP */ +#define LL_DBGMCU_APB1_GRP1_RTC_STOP DBGMCU_APB1_FZ_DBG_RTC_STOP /*!< RTC counter stopped when core is halted */ +#define LL_DBGMCU_APB1_GRP1_WWDG_STOP DBGMCU_APB1_FZ_DBG_WWDG_STOP /*!< Debug Window Watchdog stopped when Core is halted */ +#define LL_DBGMCU_APB1_GRP1_IWDG_STOP DBGMCU_APB1_FZ_DBG_IWDG_STOP /*!< Debug Independent Watchdog stopped when Core is halted */ +#define LL_DBGMCU_APB1_GRP1_I2C1_STOP DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT /*!< I2C1 SMBUS timeout mode stopped when Core is halted */ +#define LL_DBGMCU_APB1_GRP1_I2C2_STOP DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT /*!< I2C2 SMBUS timeout mode stopped when Core is halted */ +#if defined(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT) +#define LL_DBGMCU_APB1_GRP1_I2C3_STOP DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT /*!< I2C3 SMBUS timeout mode stopped when Core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT */ +#if defined(DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT) +#define LL_DBGMCU_APB1_GRP1_I2C4_STOP DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT /*!< I2C4 SMBUS timeout mode stopped when Core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT */ +#if defined(DBGMCU_APB1_FZ_DBG_CAN1_STOP) +#define LL_DBGMCU_APB1_GRP1_CAN1_STOP DBGMCU_APB1_FZ_DBG_CAN1_STOP /*!< CAN1 debug stopped when Core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_CAN1_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_CAN2_STOP) +#define LL_DBGMCU_APB1_GRP1_CAN2_STOP DBGMCU_APB1_FZ_DBG_CAN2_STOP /*!< CAN2 debug stopped when Core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_CAN2_STOP */ +#if defined(DBGMCU_APB1_FZ_DBG_CAN3_STOP) +#define LL_DBGMCU_APB1_GRP1_CAN3_STOP DBGMCU_APB1_FZ_DBG_CAN3_STOP /*!< CAN3 debug stopped when Core is halted */ +#endif /* DBGMCU_APB1_FZ_DBG_CAN3_STOP */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_APB2_GRP1_STOP_IP DBGMCU APB2 GRP1 STOP IP + * @{ + */ +#define LL_DBGMCU_APB2_GRP1_TIM1_STOP DBGMCU_APB2_FZ_DBG_TIM1_STOP /*!< TIM1 counter stopped when core is halted */ +#if defined(DBGMCU_APB2_FZ_DBG_TIM8_STOP) +#define LL_DBGMCU_APB2_GRP1_TIM8_STOP DBGMCU_APB2_FZ_DBG_TIM8_STOP /*!< TIM8 counter stopped when core is halted */ +#endif /* DBGMCU_APB2_FZ_DBG_TIM8_STOP */ +#define LL_DBGMCU_APB2_GRP1_TIM9_STOP DBGMCU_APB2_FZ_DBG_TIM9_STOP /*!< TIM9 counter stopped when core is halted */ +#if defined(DBGMCU_APB2_FZ_DBG_TIM10_STOP) +#define LL_DBGMCU_APB2_GRP1_TIM10_STOP DBGMCU_APB2_FZ_DBG_TIM10_STOP /*!< TIM10 counter stopped when core is halted */ +#endif /* DBGMCU_APB2_FZ_DBG_TIM10_STOP */ +#define LL_DBGMCU_APB2_GRP1_TIM11_STOP DBGMCU_APB2_FZ_DBG_TIM11_STOP /*!< TIM11 counter stopped when core is halted */ +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EC_LATENCY FLASH LATENCY + * @{ + */ +#define LL_FLASH_LATENCY_0 FLASH_ACR_LATENCY_0WS /*!< FLASH Zero wait state */ +#define LL_FLASH_LATENCY_1 FLASH_ACR_LATENCY_1WS /*!< FLASH One wait state */ +#define LL_FLASH_LATENCY_2 FLASH_ACR_LATENCY_2WS /*!< FLASH Two wait states */ +#define LL_FLASH_LATENCY_3 FLASH_ACR_LATENCY_3WS /*!< FLASH Three wait states */ +#define LL_FLASH_LATENCY_4 FLASH_ACR_LATENCY_4WS /*!< FLASH Four wait states */ +#define LL_FLASH_LATENCY_5 FLASH_ACR_LATENCY_5WS /*!< FLASH five wait state */ +#define LL_FLASH_LATENCY_6 FLASH_ACR_LATENCY_6WS /*!< FLASH six wait state */ +#define LL_FLASH_LATENCY_7 FLASH_ACR_LATENCY_7WS /*!< FLASH seven wait states */ +#define LL_FLASH_LATENCY_8 FLASH_ACR_LATENCY_8WS /*!< FLASH eight wait states */ +#define LL_FLASH_LATENCY_9 FLASH_ACR_LATENCY_9WS /*!< FLASH nine wait states */ +#define LL_FLASH_LATENCY_10 FLASH_ACR_LATENCY_10WS /*!< FLASH ten wait states */ +#define LL_FLASH_LATENCY_11 FLASH_ACR_LATENCY_11WS /*!< FLASH eleven wait states */ +#define LL_FLASH_LATENCY_12 FLASH_ACR_LATENCY_12WS /*!< FLASH twelve wait states */ +#define LL_FLASH_LATENCY_13 FLASH_ACR_LATENCY_13WS /*!< FLASH thirteen wait states */ +#define LL_FLASH_LATENCY_14 FLASH_ACR_LATENCY_14WS /*!< FLASH fourteen wait states */ +#define LL_FLASH_LATENCY_15 FLASH_ACR_LATENCY_15WS /*!< FLASH fifteen wait states */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SYSTEM_LL_Exported_Functions SYSTEM Exported Functions + * @{ + */ + +/** @defgroup SYSTEM_LL_EF_SYSCFG SYSCFG + * @{ + */ +/** + * @brief Set memory mapping at address 0x00000000 + * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_SetRemapMemory + * @param Memory This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_REMAP_FLASH + * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH + * @arg @ref LL_SYSCFG_REMAP_SRAM + * @arg @ref LL_SYSCFG_REMAP_FSMC (*) + * @arg @ref LL_SYSCFG_REMAP_FMC (*) + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_SetRemapMemory(uint32_t Memory) +{ + MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE, Memory); +} + +/** + * @brief Get memory mapping at address 0x00000000 + * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_GetRemapMemory + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_REMAP_FLASH + * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH + * @arg @ref LL_SYSCFG_REMAP_SRAM + * @arg @ref LL_SYSCFG_REMAP_FSMC (*) + * @arg @ref LL_SYSCFG_REMAP_FMC (*) + */ +__STATIC_INLINE uint32_t LL_SYSCFG_GetRemapMemory(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE)); +} + +#if defined(SYSCFG_MEMRMP_SWP_FMC) +/** + * @brief Enables the FMC Memory Mapping Swapping + * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_EnableFMCMemorySwapping + * @note SDRAM is accessible at 0x60000000 and NOR/RAM + * is accessible at 0xC0000000 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_EnableFMCMemorySwapping(void) +{ + SET_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC_0); +} + +/** + * @brief Disables the FMC Memory Mapping Swapping + * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_DisableFMCMemorySwapping + * @note SDRAM is accessible at 0xC0000000 (default mapping) + * and NOR/RAM is accessible at 0x60000000 (default mapping) + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DisableFMCMemorySwapping(void) +{ + CLEAR_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC); +} + +#endif /* SYSCFG_MEMRMP_SWP_FMC */ +/** + * @brief Enables the Compensation cell Power Down + * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_EnableCompensationCell + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_EnableCompensationCell(void) +{ + SET_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); +} + +/** + * @brief Disables the Compensation cell Power Down + * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_DisableCompensationCell + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DisableCompensationCell(void) +{ + CLEAR_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); +} + +/** + * @brief Get Compensation Cell ready Flag + * @rmtoll SYSCFG_CMPCR READY LL_SYSCFG_IsActiveFlag_CMPCR + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CMPCR(void) +{ + return (READ_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_READY) == (SYSCFG_CMPCR_READY)); +} + +#if defined(SYSCFG_PMC_MII_RMII_SEL) +/** + * @brief Select Ethernet PHY interface + * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_SetPHYInterface + * @param Interface This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_PMC_ETHMII + * @arg @ref LL_SYSCFG_PMC_ETHRMII + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_SetPHYInterface(uint32_t Interface) +{ + MODIFY_REG(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL, Interface); +} + +/** + * @brief Get Ethernet PHY interface + * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_GetPHYInterface + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_PMC_ETHMII + * @arg @ref LL_SYSCFG_PMC_ETHRMII + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_GetPHYInterface(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL)); +} +#endif /* SYSCFG_PMC_MII_RMII_SEL */ + + + +#if defined(SYSCFG_MEMRMP_UFB_MODE) +/** + * @brief Select Flash bank mode (Bank flashed at 0x08000000) + * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_SetFlashBankMode + * @param Bank This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_BANKMODE_BANK1 + * @arg @ref LL_SYSCFG_BANKMODE_BANK2 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_SetFlashBankMode(uint32_t Bank) +{ + MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE, Bank); +} + +/** + * @brief Get Flash bank mode (Bank flashed at 0x08000000) + * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_GetFlashBankMode + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_BANKMODE_BANK1 + * @arg @ref LL_SYSCFG_BANKMODE_BANK2 + */ +__STATIC_INLINE uint32_t LL_SYSCFG_GetFlashBankMode(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE)); +} +#endif /* SYSCFG_MEMRMP_UFB_MODE */ + +#if defined(SYSCFG_CFGR_FMPI2C1_SCL) +/** + * @brief Enable the I2C fast mode plus driving capability. + * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_EnableFastModePlus\n + * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_EnableFastModePlus + * @param ConfigFastModePlus This parameter can be a combination of the following values: + * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL + * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA + * (*) value not defined in all devices + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_EnableFastModePlus(uint32_t ConfigFastModePlus) +{ + SET_BIT(SYSCFG->CFGR, ConfigFastModePlus); +} + +/** + * @brief Disable the I2C fast mode plus driving capability. + * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_DisableFastModePlus\n + * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_DisableFastModePlus\n + * @param ConfigFastModePlus This parameter can be a combination of the following values: + * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL + * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA + * (*) value not defined in all devices + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DisableFastModePlus(uint32_t ConfigFastModePlus) +{ + CLEAR_BIT(SYSCFG->CFGR, ConfigFastModePlus); +} +#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ + +/** + * @brief Configure source input for the EXTI external interrupt. + * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_SetEXTISource\n + * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_SetEXTISource\n + * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_SetEXTISource\n + * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_SetEXTISource + * @param Port This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_EXTI_PORTA + * @arg @ref LL_SYSCFG_EXTI_PORTB + * @arg @ref LL_SYSCFG_EXTI_PORTC + * @arg @ref LL_SYSCFG_EXTI_PORTD + * @arg @ref LL_SYSCFG_EXTI_PORTE + * @arg @ref LL_SYSCFG_EXTI_PORTF (*) + * @arg @ref LL_SYSCFG_EXTI_PORTG (*) + * @arg @ref LL_SYSCFG_EXTI_PORTH + * + * (*) value not defined in all devices + * @param Line This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_EXTI_LINE0 + * @arg @ref LL_SYSCFG_EXTI_LINE1 + * @arg @ref LL_SYSCFG_EXTI_LINE2 + * @arg @ref LL_SYSCFG_EXTI_LINE3 + * @arg @ref LL_SYSCFG_EXTI_LINE4 + * @arg @ref LL_SYSCFG_EXTI_LINE5 + * @arg @ref LL_SYSCFG_EXTI_LINE6 + * @arg @ref LL_SYSCFG_EXTI_LINE7 + * @arg @ref LL_SYSCFG_EXTI_LINE8 + * @arg @ref LL_SYSCFG_EXTI_LINE9 + * @arg @ref LL_SYSCFG_EXTI_LINE10 + * @arg @ref LL_SYSCFG_EXTI_LINE11 + * @arg @ref LL_SYSCFG_EXTI_LINE12 + * @arg @ref LL_SYSCFG_EXTI_LINE13 + * @arg @ref LL_SYSCFG_EXTI_LINE14 + * @arg @ref LL_SYSCFG_EXTI_LINE15 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_SetEXTISource(uint32_t Port, uint32_t Line) +{ + MODIFY_REG(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16), Port << POSITION_VAL((Line >> 16))); +} + +/** + * @brief Get the configured defined for specific EXTI Line + * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_GetEXTISource\n + * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_GetEXTISource\n + * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_GetEXTISource\n + * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_GetEXTISource + * @param Line This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_EXTI_LINE0 + * @arg @ref LL_SYSCFG_EXTI_LINE1 + * @arg @ref LL_SYSCFG_EXTI_LINE2 + * @arg @ref LL_SYSCFG_EXTI_LINE3 + * @arg @ref LL_SYSCFG_EXTI_LINE4 + * @arg @ref LL_SYSCFG_EXTI_LINE5 + * @arg @ref LL_SYSCFG_EXTI_LINE6 + * @arg @ref LL_SYSCFG_EXTI_LINE7 + * @arg @ref LL_SYSCFG_EXTI_LINE8 + * @arg @ref LL_SYSCFG_EXTI_LINE9 + * @arg @ref LL_SYSCFG_EXTI_LINE10 + * @arg @ref LL_SYSCFG_EXTI_LINE11 + * @arg @ref LL_SYSCFG_EXTI_LINE12 + * @arg @ref LL_SYSCFG_EXTI_LINE13 + * @arg @ref LL_SYSCFG_EXTI_LINE14 + * @arg @ref LL_SYSCFG_EXTI_LINE15 + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_EXTI_PORTA + * @arg @ref LL_SYSCFG_EXTI_PORTB + * @arg @ref LL_SYSCFG_EXTI_PORTC + * @arg @ref LL_SYSCFG_EXTI_PORTD + * @arg @ref LL_SYSCFG_EXTI_PORTE + * @arg @ref LL_SYSCFG_EXTI_PORTF (*) + * @arg @ref LL_SYSCFG_EXTI_PORTG (*) + * @arg @ref LL_SYSCFG_EXTI_PORTH + * (*) value not defined in all devices + */ +__STATIC_INLINE uint32_t LL_SYSCFG_GetEXTISource(uint32_t Line) +{ + return (uint32_t)(READ_BIT(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16)) >> POSITION_VAL(Line >> 16)); +} + +#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) +/** + * @brief Set connections to TIM1/8 break inputs + * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n + * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs + * @param Break This parameter can be a combination of the following values: + * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP + * @arg @ref LL_SYSCFG_TIMBREAK_PVD + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_SetTIMBreakInputs(uint32_t Break) +{ + MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK, Break); +} + +/** + * @brief Get connections to TIM1/8 Break inputs + * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n + * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs + * @retval Returned value can be can be a combination of the following values: + * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP + * @arg @ref LL_SYSCFG_TIMBREAK_PVD + */ +__STATIC_INLINE uint32_t LL_SYSCFG_GetTIMBreakInputs(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK)); +} +#endif /* SYSCFG_CFGR2_LOCKUP_LOCK */ +#if defined(SYSCFG_MCHDLYCR_BSCKSEL) +/** + * @brief Select the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. + * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 + * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection(uint32_t ClockSource) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL, ClockSource); +} +/** + * @brief Get the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. + * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 + * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL)); +} +/** + * @brief Enables the DFSDM1 or DFSDM2 Delay clock + * @rmtoll SYSCFG_MCHDLYCR MCHDLYEN LL_SYSCFG_DFSDM_EnableDelayClock + * @param MCHDLY This parameter can be one of the following values + * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN + * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM_EnableDelayClock(uint32_t MCHDLY) +{ + SET_BIT(SYSCFG->MCHDLYCR, MCHDLY); +} + +/** + * @brief Disables the DFSDM1 or the DFSDM2 Delay clock + * @rmtoll SYSCFG_MCHDLYCR MCHDLY1EN LL_SYSCFG_DFSDM1_DisableDelayClock + * @param MCHDLY This parameter can be one of the following values + * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN + * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM_DisableDelayClock(uint32_t MCHDLY) +{ + CLEAR_BIT(SYSCFG->MCHDLYCR, MCHDLY); +} + +/** + * @brief Select the source for DFSDM1 or DFSDM2 DatIn0 + * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_SetDataIn0Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn0Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); +} +/** + * @brief Get the source for DFSDM1 or DFSDM2 DatIn0. + * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_GetDataIn0Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn0 + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0 + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn0Source(uint32_t Source) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); +} +/** + * @brief Select the source for DFSDM1 or DFSDM2 DatIn2 + * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_SetDataIn2Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn2Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); +} +/** + * @brief Get the source for DFSDM1 or DFSDM2 DatIn2. + * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_GetDataIn2Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn2 + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2 + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn2Source(uint32_t Source) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM4 OC2 + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK02SEL LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM4 OC2 + * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM4 OC1 + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK13SEL LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM4 OC1 + * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 + * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL)); +} + +/** + * @brief Select the DFSDM1 Clock In + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_SetClockInSourceSelection + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD + * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockInSourceSelection(uint32_t ClockSource) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG, ClockSource); +} +/** + * @brief GET the DFSDM1 Clock In + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_GetClockInSourceSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD + * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockInSourceSelection(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG)); +} + +/** + * @brief Select the DFSDM1 Clock Out + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_SetClockOutSourceSelection + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_CKOUT + * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockOutSourceSelection(uint32_t ClockSource) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL, ClockSource); +} +/** + * @brief GET the DFSDM1 Clock Out + * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_GetClockOutSourceSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM1_CKOUT + * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockOutSourceSelection(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL)); +} + +/** + * @brief Enables the DFSDM2 Delay clock + * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_EnableDelayClock + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_EnableDelayClock(void) +{ + SET_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); +} + +/** + * @brief Disables the DFSDM2 Delay clock + * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_DisableDelayClock + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_DisableDelayClock(void) +{ + CLEAR_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); +} +/** + * @brief Select the source for DFSDM2 DatIn0 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_SetDataIn0Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn0Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL, Source); +} +/** + * @brief Get the source for DFSDM2 DatIn0. + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_GetDataIn0Source + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn0Source(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL)); +} + +/** + * @brief Select the source for DFSDM2 DatIn2 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_SetDataIn2Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn2Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL, Source); +} +/** + * @brief Get the source for DFSDM2 DatIn2. + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_GetDataIn2Source + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn2Source(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL)); +} + +/** + * @brief Select the source for DFSDM2 DatIn4 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_SetDataIn4Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn4Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL, Source); +} +/** + * @brief Get the source for DFSDM2 DatIn4. + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_GetDataIn4Source + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn4Source(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL)); +} + +/** + * @brief Select the source for DFSDM2 DatIn6 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_SetDataIn6Source + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn6Source(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL, Source); +} +/** + * @brief Get the source for DFSDM2 DatIn6. + * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_GetDataIn6Source + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD + * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn6Source(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM3 OC4 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM3 OC3 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK15SEL LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM3 OC2 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK26SEL LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM3 OC2 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL)); +} + +/** + * @brief Select the distribution of the bitsream lock gated by TIM3 OC1 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution + * @param Source This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution(uint32_t Source) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL, Source); +} +/** + * @brief Get the distribution of the bitsream lock gated by TIM3 OC1 + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 + * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL)); +} + +/** + * @brief Select the DFSDM2 Clock In + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_SetClockInSourceSelection + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD + * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockInSourceSelection(uint32_t ClockSource) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG, ClockSource); +} +/** + * @brief GET the DFSDM2 Clock In + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_GetClockInSourceSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD + * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockInSourceSelection(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG)); +} + +/** + * @brief Select the DFSDM2 Clock Out + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_SetClockOutSourceSelection + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_CKOUT + * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 + * @retval None + */ +__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockOutSourceSelection(uint32_t ClockSource) +{ + MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL, ClockSource); +} +/** + * @brief GET the DFSDM2 Clock Out + * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_GetClockOutSourceSelection + * @retval Returned value can be one of the following values: + * @arg @ref LL_SYSCFG_DFSDM2_CKOUT + * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 + * @retval None + */ +__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockOutSourceSelection(void) +{ + return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL)); +} + +#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ +/** + * @} + */ + + +/** @defgroup SYSTEM_LL_EF_DBGMCU DBGMCU + * @{ + */ + +/** + * @brief Return the device identifier + * @note For STM32F405/407xx and STM32F415/417xx devices, the device ID is 0x413 + * @note For STM32F42xxx and STM32F43xxx devices, the device ID is 0x419 + * @note For STM32F401xx devices, the device ID is 0x423 + * @note For STM32F401xx devices, the device ID is 0x433 + * @note For STM32F411xx devices, the device ID is 0x431 + * @note For STM32F410xx devices, the device ID is 0x458 + * @note For STM32F412xx devices, the device ID is 0x441 + * @note For STM32F413xx and STM32423xx devices, the device ID is 0x463 + * @note For STM32F446xx devices, the device ID is 0x421 + * @note For STM32F469xx and STM32F479xx devices, the device ID is 0x434 + * @rmtoll DBGMCU_IDCODE DEV_ID LL_DBGMCU_GetDeviceID + * @retval Values between Min_Data=0x00 and Max_Data=0xFFF + */ +__STATIC_INLINE uint32_t LL_DBGMCU_GetDeviceID(void) +{ + return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_DEV_ID)); +} + +/** + * @brief Return the device revision identifier + * @note This field indicates the revision of the device. + For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001, rev1 -> 0x1003, rev2 ->0x1007, revY -> 0x100F for STM32F405/407xx and STM32F415/417xx devices + For example, it is read as RevA -> 0x1000, Cat 2 revY -> 0x1003, rev1 -> 0x1007, rev3 ->0x2001 for STM32F42xxx and STM32F43xxx devices + For example, it is read as RevZ -> 0x1000, Cat 2 revA -> 0x1001 for STM32F401xB/C devices + For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001 for STM32F401xD/E devices + For example, it is read as RevA -> 0x1000 for STM32F411xx,STM32F413/423xx,STM32F469/423xx, STM32F446xx and STM32F410xx devices + For example, it is read as RevZ -> 0x1001, Cat 2 revB -> 0x2000, revC -> 0x3000 for STM32F412xx devices + * @rmtoll DBGMCU_IDCODE REV_ID LL_DBGMCU_GetRevisionID + * @retval Values between Min_Data=0x00 and Max_Data=0xFFFF + */ +__STATIC_INLINE uint32_t LL_DBGMCU_GetRevisionID(void) +{ + return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_REV_ID) >> DBGMCU_IDCODE_REV_ID_Pos); +} + +/** + * @brief Enable the Debug Module during SLEEP mode + * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_EnableDBGSleepMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_EnableDBGSleepMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Disable the Debug Module during SLEEP mode + * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_DisableDBGSleepMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_DisableDBGSleepMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Enable the Debug Module during STOP mode + * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_EnableDBGStopMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_EnableDBGStopMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Disable the Debug Module during STOP mode + * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_DisableDBGStopMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_DisableDBGStopMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Enable the Debug Module during STANDBY mode + * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_EnableDBGStandbyMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_EnableDBGStandbyMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Disable the Debug Module during STANDBY mode + * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_DisableDBGStandbyMode + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_DisableDBGStandbyMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Set Trace pin assignment control + * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_SetTracePinAssignment\n + * DBGMCU_CR TRACE_MODE LL_DBGMCU_SetTracePinAssignment + * @param PinAssignment This parameter can be one of the following values: + * @arg @ref LL_DBGMCU_TRACE_NONE + * @arg @ref LL_DBGMCU_TRACE_ASYNCH + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_SetTracePinAssignment(uint32_t PinAssignment) +{ + MODIFY_REG(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE, PinAssignment); +} + +/** + * @brief Get Trace pin assignment control + * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_GetTracePinAssignment\n + * DBGMCU_CR TRACE_MODE LL_DBGMCU_GetTracePinAssignment + * @retval Returned value can be one of the following values: + * @arg @ref LL_DBGMCU_TRACE_NONE + * @arg @ref LL_DBGMCU_TRACE_ASYNCH + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 + * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 + */ +__STATIC_INLINE uint32_t LL_DBGMCU_GetTracePinAssignment(void) +{ + return (uint32_t)(READ_BIT(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE)); +} + +/** + * @brief Freeze APB1 peripherals (group1 peripherals) + * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_FreezePeriph(uint32_t Periphs) +{ + SET_BIT(DBGMCU->APB1FZ, Periphs); +} + +/** + * @brief Unfreeze APB1 peripherals (group1 peripherals) + * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n + * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) + * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_UnFreezePeriph(uint32_t Periphs) +{ + CLEAR_BIT(DBGMCU->APB1FZ, Periphs); +} + +/** + * @brief Freeze APB2 peripherals + * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_FreezePeriph(uint32_t Periphs) +{ + SET_BIT(DBGMCU->APB2FZ, Periphs); +} + +/** + * @brief Unfreeze APB2 peripherals + * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n + * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph + * @param Periphs This parameter can be a combination of the following values: + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) + * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) + * + * (*) value not defined in all devices. + * @retval None + */ +__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_UnFreezePeriph(uint32_t Periphs) +{ + CLEAR_BIT(DBGMCU->APB2FZ, Periphs); +} +/** + * @} + */ + +/** @defgroup SYSTEM_LL_EF_FLASH FLASH + * @{ + */ + +/** + * @brief Set FLASH Latency + * @rmtoll FLASH_ACR LATENCY LL_FLASH_SetLatency + * @param Latency This parameter can be one of the following values: + * @arg @ref LL_FLASH_LATENCY_0 + * @arg @ref LL_FLASH_LATENCY_1 + * @arg @ref LL_FLASH_LATENCY_2 + * @arg @ref LL_FLASH_LATENCY_3 + * @arg @ref LL_FLASH_LATENCY_4 + * @arg @ref LL_FLASH_LATENCY_5 + * @arg @ref LL_FLASH_LATENCY_6 + * @arg @ref LL_FLASH_LATENCY_7 + * @arg @ref LL_FLASH_LATENCY_8 + * @arg @ref LL_FLASH_LATENCY_9 + * @arg @ref LL_FLASH_LATENCY_10 + * @arg @ref LL_FLASH_LATENCY_11 + * @arg @ref LL_FLASH_LATENCY_12 + * @arg @ref LL_FLASH_LATENCY_13 + * @arg @ref LL_FLASH_LATENCY_14 + * @arg @ref LL_FLASH_LATENCY_15 + * @retval None + */ +__STATIC_INLINE void LL_FLASH_SetLatency(uint32_t Latency) +{ + MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, Latency); +} + +/** + * @brief Get FLASH Latency + * @rmtoll FLASH_ACR LATENCY LL_FLASH_GetLatency + * @retval Returned value can be one of the following values: + * @arg @ref LL_FLASH_LATENCY_0 + * @arg @ref LL_FLASH_LATENCY_1 + * @arg @ref LL_FLASH_LATENCY_2 + * @arg @ref LL_FLASH_LATENCY_3 + * @arg @ref LL_FLASH_LATENCY_4 + * @arg @ref LL_FLASH_LATENCY_5 + * @arg @ref LL_FLASH_LATENCY_6 + * @arg @ref LL_FLASH_LATENCY_7 + * @arg @ref LL_FLASH_LATENCY_8 + * @arg @ref LL_FLASH_LATENCY_9 + * @arg @ref LL_FLASH_LATENCY_10 + * @arg @ref LL_FLASH_LATENCY_11 + * @arg @ref LL_FLASH_LATENCY_12 + * @arg @ref LL_FLASH_LATENCY_13 + * @arg @ref LL_FLASH_LATENCY_14 + * @arg @ref LL_FLASH_LATENCY_15 + */ +__STATIC_INLINE uint32_t LL_FLASH_GetLatency(void) +{ + return (uint32_t)(READ_BIT(FLASH->ACR, FLASH_ACR_LATENCY)); +} + +/** + * @brief Enable Prefetch + * @rmtoll FLASH_ACR PRFTEN LL_FLASH_EnablePrefetch + * @retval None + */ +__STATIC_INLINE void LL_FLASH_EnablePrefetch(void) +{ + SET_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); +} + +/** + * @brief Disable Prefetch + * @rmtoll FLASH_ACR PRFTEN LL_FLASH_DisablePrefetch + * @retval None + */ +__STATIC_INLINE void LL_FLASH_DisablePrefetch(void) +{ + CLEAR_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); +} + +/** + * @brief Check if Prefetch buffer is enabled + * @rmtoll FLASH_ACR PRFTEN LL_FLASH_IsPrefetchEnabled + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_FLASH_IsPrefetchEnabled(void) +{ + return (READ_BIT(FLASH->ACR, FLASH_ACR_PRFTEN) == (FLASH_ACR_PRFTEN)); +} + +/** + * @brief Enable Instruction cache + * @rmtoll FLASH_ACR ICEN LL_FLASH_EnableInstCache + * @retval None + */ +__STATIC_INLINE void LL_FLASH_EnableInstCache(void) +{ + SET_BIT(FLASH->ACR, FLASH_ACR_ICEN); +} + +/** + * @brief Disable Instruction cache + * @rmtoll FLASH_ACR ICEN LL_FLASH_DisableInstCache + * @retval None + */ +__STATIC_INLINE void LL_FLASH_DisableInstCache(void) +{ + CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICEN); +} + +/** + * @brief Enable Data cache + * @rmtoll FLASH_ACR DCEN LL_FLASH_EnableDataCache + * @retval None + */ +__STATIC_INLINE void LL_FLASH_EnableDataCache(void) +{ + SET_BIT(FLASH->ACR, FLASH_ACR_DCEN); +} + +/** + * @brief Disable Data cache + * @rmtoll FLASH_ACR DCEN LL_FLASH_DisableDataCache + * @retval None + */ +__STATIC_INLINE void LL_FLASH_DisableDataCache(void) +{ + CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCEN); +} + +/** + * @brief Enable Instruction cache reset + * @note bit can be written only when the instruction cache is disabled + * @rmtoll FLASH_ACR ICRST LL_FLASH_EnableInstCacheReset + * @retval None + */ +__STATIC_INLINE void LL_FLASH_EnableInstCacheReset(void) +{ + SET_BIT(FLASH->ACR, FLASH_ACR_ICRST); +} + +/** + * @brief Disable Instruction cache reset + * @rmtoll FLASH_ACR ICRST LL_FLASH_DisableInstCacheReset + * @retval None + */ +__STATIC_INLINE void LL_FLASH_DisableInstCacheReset(void) +{ + CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICRST); +} + +/** + * @brief Enable Data cache reset + * @note bit can be written only when the data cache is disabled + * @rmtoll FLASH_ACR DCRST LL_FLASH_EnableDataCacheReset + * @retval None + */ +__STATIC_INLINE void LL_FLASH_EnableDataCacheReset(void) +{ + SET_BIT(FLASH->ACR, FLASH_ACR_DCRST); +} + +/** + * @brief Disable Data cache reset + * @rmtoll FLASH_ACR DCRST LL_FLASH_DisableDataCacheReset + * @retval None + */ +__STATIC_INLINE void LL_FLASH_DisableDataCacheReset(void) +{ + CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCRST); +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_SYSTEM_H */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h new file mode 100644 index 0000000..cf6ca38 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h @@ -0,0 +1,4093 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_tim.h + * @author MCD Application Team + * @brief Header file of TIM LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_TIM_H +#define __STM32F4xx_LL_TIM_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14) + +/** @defgroup TIM_LL TIM + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup TIM_LL_Private_Variables TIM Private Variables + * @{ + */ +static const uint8_t OFFSET_TAB_CCMRx[] = +{ + 0x00U, /* 0: TIMx_CH1 */ + 0x00U, /* 1: TIMx_CH1N */ + 0x00U, /* 2: TIMx_CH2 */ + 0x00U, /* 3: TIMx_CH2N */ + 0x04U, /* 4: TIMx_CH3 */ + 0x04U, /* 5: TIMx_CH3N */ + 0x04U /* 6: TIMx_CH4 */ +}; + +static const uint8_t SHIFT_TAB_OCxx[] = +{ + 0U, /* 0: OC1M, OC1FE, OC1PE */ + 0U, /* 1: - NA */ + 8U, /* 2: OC2M, OC2FE, OC2PE */ + 0U, /* 3: - NA */ + 0U, /* 4: OC3M, OC3FE, OC3PE */ + 0U, /* 5: - NA */ + 8U /* 6: OC4M, OC4FE, OC4PE */ +}; + +static const uint8_t SHIFT_TAB_ICxx[] = +{ + 0U, /* 0: CC1S, IC1PSC, IC1F */ + 0U, /* 1: - NA */ + 8U, /* 2: CC2S, IC2PSC, IC2F */ + 0U, /* 3: - NA */ + 0U, /* 4: CC3S, IC3PSC, IC3F */ + 0U, /* 5: - NA */ + 8U /* 6: CC4S, IC4PSC, IC4F */ +}; + +static const uint8_t SHIFT_TAB_CCxP[] = +{ + 0U, /* 0: CC1P */ + 2U, /* 1: CC1NP */ + 4U, /* 2: CC2P */ + 6U, /* 3: CC2NP */ + 8U, /* 4: CC3P */ + 10U, /* 5: CC3NP */ + 12U /* 6: CC4P */ +}; + +static const uint8_t SHIFT_TAB_OISx[] = +{ + 0U, /* 0: OIS1 */ + 1U, /* 1: OIS1N */ + 2U, /* 2: OIS2 */ + 3U, /* 3: OIS2N */ + 4U, /* 4: OIS3 */ + 5U, /* 5: OIS3N */ + 6U /* 6: OIS4 */ +}; +/** + * @} + */ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup TIM_LL_Private_Constants TIM Private Constants + * @{ + */ + + +/* Remap mask definitions */ +#define TIMx_OR_RMP_SHIFT 16U +#define TIMx_OR_RMP_MASK 0x0000FFFFU +#define TIM2_OR_RMP_MASK (TIM_OR_ITR1_RMP << TIMx_OR_RMP_SHIFT) +#define TIM5_OR_RMP_MASK (TIM_OR_TI4_RMP << TIMx_OR_RMP_SHIFT) +#define TIM11_OR_RMP_MASK (TIM_OR_TI1_RMP << TIMx_OR_RMP_SHIFT) + +/* Mask used to set the TDG[x:0] of the DTG bits of the TIMx_BDTR register */ +#define DT_DELAY_1 ((uint8_t)0x7F) +#define DT_DELAY_2 ((uint8_t)0x3F) +#define DT_DELAY_3 ((uint8_t)0x1F) +#define DT_DELAY_4 ((uint8_t)0x1F) + +/* Mask used to set the DTG[7:5] bits of the DTG bits of the TIMx_BDTR register */ +#define DT_RANGE_1 ((uint8_t)0x00) +#define DT_RANGE_2 ((uint8_t)0x80) +#define DT_RANGE_3 ((uint8_t)0xC0) +#define DT_RANGE_4 ((uint8_t)0xE0) + + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup TIM_LL_Private_Macros TIM Private Macros + * @{ + */ +/** @brief Convert channel id into channel index. + * @param __CHANNEL__ This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval none + */ +#define TIM_GET_CHANNEL_INDEX( __CHANNEL__) \ + (((__CHANNEL__) == LL_TIM_CHANNEL_CH1) ? 0U :\ + ((__CHANNEL__) == LL_TIM_CHANNEL_CH1N) ? 1U :\ + ((__CHANNEL__) == LL_TIM_CHANNEL_CH2) ? 2U :\ + ((__CHANNEL__) == LL_TIM_CHANNEL_CH2N) ? 3U :\ + ((__CHANNEL__) == LL_TIM_CHANNEL_CH3) ? 4U :\ + ((__CHANNEL__) == LL_TIM_CHANNEL_CH3N) ? 5U : 6U) + +/** @brief Calculate the deadtime sampling period(in ps). + * @param __TIMCLK__ timer input clock frequency (in Hz). + * @param __CKD__ This parameter can be one of the following values: + * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 + * @retval none + */ +#define TIM_CALC_DTS(__TIMCLK__, __CKD__) \ + (((__CKD__) == LL_TIM_CLOCKDIVISION_DIV1) ? ((uint64_t)1000000000000U/(__TIMCLK__)) : \ + ((__CKD__) == LL_TIM_CLOCKDIVISION_DIV2) ? ((uint64_t)1000000000000U/((__TIMCLK__) >> 1U)) : \ + ((uint64_t)1000000000000U/((__TIMCLK__) >> 2U))) +/** + * @} + */ + + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup TIM_LL_ES_INIT TIM Exported Init structure + * @{ + */ + +/** + * @brief TIM Time Base configuration structure definition. + */ +typedef struct +{ + uint16_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetPrescaler().*/ + + uint32_t CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_LL_EC_COUNTERMODE. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetCounterMode().*/ + + uint32_t Autoreload; /*!< Specifies the auto reload value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between Min_Data=0x0000 and Max_Data=0xFFFF. + Some timer instances may support 32 bits counters. In that case this parameter must + be a number between 0x0000 and 0xFFFFFFFF. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetAutoReload().*/ + + uint32_t ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_LL_EC_CLOCKDIVISION. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetClockDivision().*/ + + uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + GP timers: this parameter must be a number between Min_Data = 0x00 and + Max_Data = 0xFF. + Advanced timers: this parameter must be a number between Min_Data = 0x0000 and + Max_Data = 0xFFFF. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetRepetitionCounter().*/ +} LL_TIM_InitTypeDef; + +/** + * @brief TIM Output Compare configuration structure definition. + */ +typedef struct +{ + uint32_t OCMode; /*!< Specifies the output mode. + This parameter can be a value of @ref TIM_LL_EC_OCMODE. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetMode().*/ + + uint32_t OCState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_LL_EC_OCSTATE. + + This feature can be modified afterwards using unitary functions + @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ + + uint32_t OCNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_LL_EC_OCSTATE. + + This feature can be modified afterwards using unitary functions + @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ + + uint32_t CompareValue; /*!< Specifies the Compare value to be loaded into the Capture Compare Register. + This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. + + This feature can be modified afterwards using unitary function + LL_TIM_OC_SetCompareCHx (x=1..6).*/ + + uint32_t OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetPolarity().*/ + + uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetPolarity().*/ + + + uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetIdleState().*/ + + uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetIdleState().*/ +} LL_TIM_OC_InitTypeDef; + +/** + * @brief TIM Input Capture configuration structure definition. + */ + +typedef struct +{ + + uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPolarity().*/ + + uint32_t ICActiveInput; /*!< Specifies the input. + This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetActiveInput().*/ + + uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_LL_EC_ICPSC. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPrescaler().*/ + + uint32_t ICFilter; /*!< Specifies the input capture filter. + This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetFilter().*/ +} LL_TIM_IC_InitTypeDef; + + +/** + * @brief TIM Encoder interface configuration structure definition. + */ +typedef struct +{ + uint32_t EncoderMode; /*!< Specifies the encoder resolution (x2 or x4). + This parameter can be a value of @ref TIM_LL_EC_ENCODERMODE. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetEncoderMode().*/ + + uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. + This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPolarity().*/ + + uint32_t IC1ActiveInput; /*!< Specifies the TI1 input source + This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetActiveInput().*/ + + uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. + This parameter can be a value of @ref TIM_LL_EC_ICPSC. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPrescaler().*/ + + uint32_t IC1Filter; /*!< Specifies the TI1 input filter. + This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetFilter().*/ + + uint32_t IC2Polarity; /*!< Specifies the active edge of TI2 input. + This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPolarity().*/ + + uint32_t IC2ActiveInput; /*!< Specifies the TI2 input source + This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetActiveInput().*/ + + uint32_t IC2Prescaler; /*!< Specifies the TI2 input prescaler value. + This parameter can be a value of @ref TIM_LL_EC_ICPSC. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPrescaler().*/ + + uint32_t IC2Filter; /*!< Specifies the TI2 input filter. + This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetFilter().*/ + +} LL_TIM_ENCODER_InitTypeDef; + +/** + * @brief TIM Hall sensor interface configuration structure definition. + */ +typedef struct +{ + + uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. + This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPolarity().*/ + + uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. + Prescaler must be set to get a maximum counter period longer than the + time interval between 2 consecutive changes on the Hall inputs. + This parameter can be a value of @ref TIM_LL_EC_ICPSC. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetPrescaler().*/ + + uint32_t IC1Filter; /*!< Specifies the TI1 input filter. + This parameter can be a value of + @ref TIM_LL_EC_IC_FILTER. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_IC_SetFilter().*/ + + uint32_t CommutationDelay; /*!< Specifies the compare value to be loaded into the Capture Compare Register. + A positive pulse (TRGO event) is generated with a programmable delay every time + a change occurs on the Hall inputs. + This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetCompareCH2().*/ +} LL_TIM_HALLSENSOR_InitTypeDef; + +/** + * @brief BDTR (Break and Dead Time) structure definition + */ +typedef struct +{ + uint32_t OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref TIM_LL_EC_OSSR + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetOffStates() + + @note This bit-field cannot be modified as long as LOCK level 2 has been + programmed. */ + + uint32_t OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref TIM_LL_EC_OSSI + + This feature can be modified afterwards using unitary function + @ref LL_TIM_SetOffStates() + + @note This bit-field cannot be modified as long as LOCK level 2 has been + programmed. */ + + uint32_t LockLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref TIM_LL_EC_LOCKLEVEL + + @note The LOCK bits can be written only once after the reset. Once the TIMx_BDTR + register has been written, their content is frozen until the next reset.*/ + + uint8_t DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF. + + This feature can be modified afterwards using unitary function + @ref LL_TIM_OC_SetDeadTime() + + @note This bit-field can not be modified as long as LOCK level 1, 2 or 3 has been + programmed. */ + + uint16_t BreakState; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref TIM_LL_EC_BREAK_ENABLE + + This feature can be modified afterwards using unitary functions + @ref LL_TIM_EnableBRK() or @ref LL_TIM_DisableBRK() + + @note This bit-field can not be modified as long as LOCK level 1 has been + programmed. */ + + uint32_t BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref TIM_LL_EC_BREAK_POLARITY + + This feature can be modified afterwards using unitary function + @ref LL_TIM_ConfigBRK() + + @note This bit-field can not be modified as long as LOCK level 1 has been + programmed. */ + + uint32_t AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_LL_EC_AUTOMATICOUTPUT_ENABLE + + This feature can be modified afterwards using unitary functions + @ref LL_TIM_EnableAutomaticOutput() or @ref LL_TIM_DisableAutomaticOutput() + + @note This bit-field can not be modified as long as LOCK level 1 has been + programmed. */ +} LL_TIM_BDTR_InitTypeDef; + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup TIM_LL_Exported_Constants TIM Exported Constants + * @{ + */ + +/** @defgroup TIM_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_TIM_ReadReg function. + * @{ + */ +#define LL_TIM_SR_UIF TIM_SR_UIF /*!< Update interrupt flag */ +#define LL_TIM_SR_CC1IF TIM_SR_CC1IF /*!< Capture/compare 1 interrupt flag */ +#define LL_TIM_SR_CC2IF TIM_SR_CC2IF /*!< Capture/compare 2 interrupt flag */ +#define LL_TIM_SR_CC3IF TIM_SR_CC3IF /*!< Capture/compare 3 interrupt flag */ +#define LL_TIM_SR_CC4IF TIM_SR_CC4IF /*!< Capture/compare 4 interrupt flag */ +#define LL_TIM_SR_COMIF TIM_SR_COMIF /*!< COM interrupt flag */ +#define LL_TIM_SR_TIF TIM_SR_TIF /*!< Trigger interrupt flag */ +#define LL_TIM_SR_BIF TIM_SR_BIF /*!< Break interrupt flag */ +#define LL_TIM_SR_CC1OF TIM_SR_CC1OF /*!< Capture/Compare 1 overcapture flag */ +#define LL_TIM_SR_CC2OF TIM_SR_CC2OF /*!< Capture/Compare 2 overcapture flag */ +#define LL_TIM_SR_CC3OF TIM_SR_CC3OF /*!< Capture/Compare 3 overcapture flag */ +#define LL_TIM_SR_CC4OF TIM_SR_CC4OF /*!< Capture/Compare 4 overcapture flag */ +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup TIM_LL_EC_BREAK_ENABLE Break Enable + * @{ + */ +#define LL_TIM_BREAK_DISABLE 0x00000000U /*!< Break function disabled */ +#define LL_TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break function enabled */ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_AUTOMATICOUTPUT_ENABLE Automatic output enable + * @{ + */ +#define LL_TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ +#define LL_TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event */ +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** @defgroup TIM_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_TIM_ReadReg and LL_TIM_WriteReg functions. + * @{ + */ +#define LL_TIM_DIER_UIE TIM_DIER_UIE /*!< Update interrupt enable */ +#define LL_TIM_DIER_CC1IE TIM_DIER_CC1IE /*!< Capture/compare 1 interrupt enable */ +#define LL_TIM_DIER_CC2IE TIM_DIER_CC2IE /*!< Capture/compare 2 interrupt enable */ +#define LL_TIM_DIER_CC3IE TIM_DIER_CC3IE /*!< Capture/compare 3 interrupt enable */ +#define LL_TIM_DIER_CC4IE TIM_DIER_CC4IE /*!< Capture/compare 4 interrupt enable */ +#define LL_TIM_DIER_COMIE TIM_DIER_COMIE /*!< COM interrupt enable */ +#define LL_TIM_DIER_TIE TIM_DIER_TIE /*!< Trigger interrupt enable */ +#define LL_TIM_DIER_BIE TIM_DIER_BIE /*!< Break interrupt enable */ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_UPDATESOURCE Update Source + * @{ + */ +#define LL_TIM_UPDATESOURCE_REGULAR 0x00000000U /*!< Counter overflow/underflow, Setting the UG bit or Update generation through the slave mode controller generates an update request */ +#define LL_TIM_UPDATESOURCE_COUNTER TIM_CR1_URS /*!< Only counter overflow/underflow generates an update request */ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_ONEPULSEMODE One Pulse Mode + * @{ + */ +#define LL_TIM_ONEPULSEMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ +#define LL_TIM_ONEPULSEMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode + * @{ + */ +#define LL_TIM_COUNTERMODE_UP 0x00000000U /*!TIMx_CCRy else active.*/ +#define LL_TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!TIMx_CCRy else inactive*/ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_OCPOLARITY Output Configuration Polarity + * @{ + */ +#define LL_TIM_OCPOLARITY_HIGH 0x00000000U /*!< OCxactive high*/ +#define LL_TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< OCxactive low*/ +/** + * @} + */ + +/** @defgroup TIM_LL_EC_OCIDLESTATE Output Configuration Idle State + * @{ + */ +#define LL_TIM_OCIDLESTATE_LOW 0x00000000U /*!__REG__, (__VALUE__)) + +/** + * @brief Read a value in TIM register. + * @param __INSTANCE__ TIM Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_TIM_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) +/** + * @} + */ + +/** @defgroup TIM_LL_EM_Exported_Macros Exported_Macros + * @{ + */ + +/** + * @brief HELPER macro calculating DTG[0:7] in the TIMx_BDTR register to achieve the requested dead time duration. + * @note ex: @ref __LL_TIM_CALC_DEADTIME (80000000, @ref LL_TIM_GetClockDivision (), 120); + * @param __TIMCLK__ timer input clock frequency (in Hz) + * @param __CKD__ This parameter can be one of the following values: + * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 + * @param __DT__ deadtime duration (in ns) + * @retval DTG[0:7] + */ +#define __LL_TIM_CALC_DEADTIME(__TIMCLK__, __CKD__, __DT__) \ + ( (((uint64_t)((__DT__)*1000U)) < ((DT_DELAY_1+1U) * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ + (uint8_t)(((uint64_t)((__DT__)*1000U) / TIM_CALC_DTS((__TIMCLK__), (__CKD__))) & DT_DELAY_1) : \ + (((uint64_t)((__DT__)*1000U)) < ((64U + (DT_DELAY_2+1U)) * 2U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ + (uint8_t)(DT_RANGE_2 | ((uint8_t)((uint8_t)((((uint64_t)((__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ + (__CKD__))) >> 1U) - (uint8_t) 64) & DT_DELAY_2)) :\ + (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_3+1U)) * 8U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ + (uint8_t)(DT_RANGE_3 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ + (__CKD__))) >> 3U) - (uint8_t) 32) & DT_DELAY_3)) :\ + (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_4+1U)) * 16U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ + (uint8_t)(DT_RANGE_4 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ + (__CKD__))) >> 4U) - (uint8_t) 32) & DT_DELAY_4)) :\ + 0U) + +/** + * @brief HELPER macro calculating the prescaler value to achieve the required counter clock frequency. + * @note ex: @ref __LL_TIM_CALC_PSC (80000000, 1000000); + * @param __TIMCLK__ timer input clock frequency (in Hz) + * @param __CNTCLK__ counter clock frequency (in Hz) + * @retval Prescaler value (between Min_Data=0 and Max_Data=65535) + */ +#define __LL_TIM_CALC_PSC(__TIMCLK__, __CNTCLK__) \ + (((__TIMCLK__) >= (__CNTCLK__)) ? (uint32_t)((((__TIMCLK__) + (__CNTCLK__)/2U)/(__CNTCLK__)) - 1U) : 0U) + +/** + * @brief HELPER macro calculating the auto-reload value to achieve the required output signal frequency. + * @note ex: @ref __LL_TIM_CALC_ARR (1000000, @ref LL_TIM_GetPrescaler (), 10000); + * @param __TIMCLK__ timer input clock frequency (in Hz) + * @param __PSC__ prescaler + * @param __FREQ__ output signal frequency (in Hz) + * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) + */ +#define __LL_TIM_CALC_ARR(__TIMCLK__, __PSC__, __FREQ__) \ + ((((__TIMCLK__)/((__PSC__) + 1U)) >= (__FREQ__)) ? (((__TIMCLK__)/((__FREQ__) * ((__PSC__) + 1U))) - 1U) : 0U) + +/** + * @brief HELPER macro calculating the compare value required to achieve the required timer output compare + * active/inactive delay. + * @note ex: @ref __LL_TIM_CALC_DELAY (1000000, @ref LL_TIM_GetPrescaler (), 10); + * @param __TIMCLK__ timer input clock frequency (in Hz) + * @param __PSC__ prescaler + * @param __DELAY__ timer output compare active/inactive delay (in us) + * @retval Compare value (between Min_Data=0 and Max_Data=65535) + */ +#define __LL_TIM_CALC_DELAY(__TIMCLK__, __PSC__, __DELAY__) \ + ((uint32_t)(((uint64_t)(__TIMCLK__) * (uint64_t)(__DELAY__)) \ + / ((uint64_t)1000000U * (uint64_t)((__PSC__) + 1U)))) + +/** + * @brief HELPER macro calculating the auto-reload value to achieve the required pulse duration + * (when the timer operates in one pulse mode). + * @note ex: @ref __LL_TIM_CALC_PULSE (1000000, @ref LL_TIM_GetPrescaler (), 10, 20); + * @param __TIMCLK__ timer input clock frequency (in Hz) + * @param __PSC__ prescaler + * @param __DELAY__ timer output compare active/inactive delay (in us) + * @param __PULSE__ pulse duration (in us) + * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) + */ +#define __LL_TIM_CALC_PULSE(__TIMCLK__, __PSC__, __DELAY__, __PULSE__) \ + ((uint32_t)(__LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__PULSE__)) \ + + __LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__DELAY__)))) + +/** + * @brief HELPER macro retrieving the ratio of the input capture prescaler + * @note ex: @ref __LL_TIM_GET_ICPSC_RATIO (@ref LL_TIM_IC_GetPrescaler ()); + * @param __ICPSC__ This parameter can be one of the following values: + * @arg @ref LL_TIM_ICPSC_DIV1 + * @arg @ref LL_TIM_ICPSC_DIV2 + * @arg @ref LL_TIM_ICPSC_DIV4 + * @arg @ref LL_TIM_ICPSC_DIV8 + * @retval Input capture prescaler ratio (1, 2, 4 or 8) + */ +#define __LL_TIM_GET_ICPSC_RATIO(__ICPSC__) \ + ((uint32_t)(0x01U << (((__ICPSC__) >> 16U) >> TIM_CCMR1_IC1PSC_Pos))) + + +/** + * @} + */ + + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup TIM_LL_Exported_Functions TIM Exported Functions + * @{ + */ + +/** @defgroup TIM_LL_EF_Time_Base Time Base configuration + * @{ + */ +/** + * @brief Enable timer counter. + * @rmtoll CR1 CEN LL_TIM_EnableCounter + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableCounter(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->CR1, TIM_CR1_CEN); +} + +/** + * @brief Disable timer counter. + * @rmtoll CR1 CEN LL_TIM_DisableCounter + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableCounter(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->CR1, TIM_CR1_CEN); +} + +/** + * @brief Indicates whether the timer counter is enabled. + * @rmtoll CR1 CEN LL_TIM_IsEnabledCounter + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledCounter(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->CR1, TIM_CR1_CEN) == (TIM_CR1_CEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable update event generation. + * @rmtoll CR1 UDIS LL_TIM_EnableUpdateEvent + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableUpdateEvent(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->CR1, TIM_CR1_UDIS); +} + +/** + * @brief Disable update event generation. + * @rmtoll CR1 UDIS LL_TIM_DisableUpdateEvent + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableUpdateEvent(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->CR1, TIM_CR1_UDIS); +} + +/** + * @brief Indicates whether update event generation is enabled. + * @rmtoll CR1 UDIS LL_TIM_IsEnabledUpdateEvent + * @param TIMx Timer instance + * @retval Inverted state of bit (0 or 1). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledUpdateEvent(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->CR1, TIM_CR1_UDIS) == (uint32_t)RESET) ? 1UL : 0UL); +} + +/** + * @brief Set update event source + * @note Update event source set to LL_TIM_UPDATESOURCE_REGULAR: any of the following events + * generate an update interrupt or DMA request if enabled: + * - Counter overflow/underflow + * - Setting the UG bit + * - Update generation through the slave mode controller + * @note Update event source set to LL_TIM_UPDATESOURCE_COUNTER: only counter + * overflow/underflow generates an update interrupt or DMA request if enabled. + * @rmtoll CR1 URS LL_TIM_SetUpdateSource + * @param TIMx Timer instance + * @param UpdateSource This parameter can be one of the following values: + * @arg @ref LL_TIM_UPDATESOURCE_REGULAR + * @arg @ref LL_TIM_UPDATESOURCE_COUNTER + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetUpdateSource(TIM_TypeDef *TIMx, uint32_t UpdateSource) +{ + MODIFY_REG(TIMx->CR1, TIM_CR1_URS, UpdateSource); +} + +/** + * @brief Get actual event update source + * @rmtoll CR1 URS LL_TIM_GetUpdateSource + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_UPDATESOURCE_REGULAR + * @arg @ref LL_TIM_UPDATESOURCE_COUNTER + */ +__STATIC_INLINE uint32_t LL_TIM_GetUpdateSource(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_URS)); +} + +/** + * @brief Set one pulse mode (one shot v.s. repetitive). + * @rmtoll CR1 OPM LL_TIM_SetOnePulseMode + * @param TIMx Timer instance + * @param OnePulseMode This parameter can be one of the following values: + * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE + * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetOnePulseMode(TIM_TypeDef *TIMx, uint32_t OnePulseMode) +{ + MODIFY_REG(TIMx->CR1, TIM_CR1_OPM, OnePulseMode); +} + +/** + * @brief Get actual one pulse mode. + * @rmtoll CR1 OPM LL_TIM_GetOnePulseMode + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE + * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE + */ +__STATIC_INLINE uint32_t LL_TIM_GetOnePulseMode(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_OPM)); +} + +/** + * @brief Set the timer counter counting mode. + * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to + * check whether or not the counter mode selection feature is supported + * by a timer instance. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * @rmtoll CR1 DIR LL_TIM_SetCounterMode\n + * CR1 CMS LL_TIM_SetCounterMode + * @param TIMx Timer instance + * @param CounterMode This parameter can be one of the following values: + * @arg @ref LL_TIM_COUNTERMODE_UP + * @arg @ref LL_TIM_COUNTERMODE_DOWN + * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP + * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN + * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetCounterMode(TIM_TypeDef *TIMx, uint32_t CounterMode) +{ + MODIFY_REG(TIMx->CR1, (TIM_CR1_DIR | TIM_CR1_CMS), CounterMode); +} + +/** + * @brief Get actual counter mode. + * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to + * check whether or not the counter mode selection feature is supported + * by a timer instance. + * @rmtoll CR1 DIR LL_TIM_GetCounterMode\n + * CR1 CMS LL_TIM_GetCounterMode + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_COUNTERMODE_UP + * @arg @ref LL_TIM_COUNTERMODE_DOWN + * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP + * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN + * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN + */ +__STATIC_INLINE uint32_t LL_TIM_GetCounterMode(TIM_TypeDef *TIMx) +{ + uint32_t counter_mode; + + counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CMS)); + + if (counter_mode == 0U) + { + counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); + } + + return counter_mode; +} + +/** + * @brief Enable auto-reload (ARR) preload. + * @rmtoll CR1 ARPE LL_TIM_EnableARRPreload + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableARRPreload(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->CR1, TIM_CR1_ARPE); +} + +/** + * @brief Disable auto-reload (ARR) preload. + * @rmtoll CR1 ARPE LL_TIM_DisableARRPreload + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableARRPreload(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->CR1, TIM_CR1_ARPE); +} + +/** + * @brief Indicates whether auto-reload (ARR) preload is enabled. + * @rmtoll CR1 ARPE LL_TIM_IsEnabledARRPreload + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledARRPreload(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->CR1, TIM_CR1_ARPE) == (TIM_CR1_ARPE)) ? 1UL : 0UL); +} + +/** + * @brief Set the division ratio between the timer clock and the sampling clock used by the dead-time generators + * (when supported) and the digital filters. + * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check + * whether or not the clock division feature is supported by the timer + * instance. + * @rmtoll CR1 CKD LL_TIM_SetClockDivision + * @param TIMx Timer instance + * @param ClockDivision This parameter can be one of the following values: + * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetClockDivision(TIM_TypeDef *TIMx, uint32_t ClockDivision) +{ + MODIFY_REG(TIMx->CR1, TIM_CR1_CKD, ClockDivision); +} + +/** + * @brief Get the actual division ratio between the timer clock and the sampling clock used by the dead-time + * generators (when supported) and the digital filters. + * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check + * whether or not the clock division feature is supported by the timer + * instance. + * @rmtoll CR1 CKD LL_TIM_GetClockDivision + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 + * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 + */ +__STATIC_INLINE uint32_t LL_TIM_GetClockDivision(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CKD)); +} + +/** + * @brief Set the counter value. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @rmtoll CNT CNT LL_TIM_SetCounter + * @param TIMx Timer instance + * @param Counter Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetCounter(TIM_TypeDef *TIMx, uint32_t Counter) +{ + WRITE_REG(TIMx->CNT, Counter); +} + +/** + * @brief Get the counter value. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @rmtoll CNT CNT LL_TIM_GetCounter + * @param TIMx Timer instance + * @retval Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) + */ +__STATIC_INLINE uint32_t LL_TIM_GetCounter(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CNT)); +} + +/** + * @brief Get the current direction of the counter + * @rmtoll CR1 DIR LL_TIM_GetDirection + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_COUNTERDIRECTION_UP + * @arg @ref LL_TIM_COUNTERDIRECTION_DOWN + */ +__STATIC_INLINE uint32_t LL_TIM_GetDirection(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); +} + +/** + * @brief Set the prescaler value. + * @note The counter clock frequency CK_CNT is equal to fCK_PSC / (PSC[15:0] + 1). + * @note The prescaler can be changed on the fly as this control register is buffered. The new + * prescaler ratio is taken into account at the next update event. + * @note Helper macro @ref __LL_TIM_CALC_PSC can be used to calculate the Prescaler parameter + * @rmtoll PSC PSC LL_TIM_SetPrescaler + * @param TIMx Timer instance + * @param Prescaler between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Prescaler) +{ + WRITE_REG(TIMx->PSC, Prescaler); +} + +/** + * @brief Get the prescaler value. + * @rmtoll PSC PSC LL_TIM_GetPrescaler + * @param TIMx Timer instance + * @retval Prescaler value between Min_Data=0 and Max_Data=65535 + */ +__STATIC_INLINE uint32_t LL_TIM_GetPrescaler(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->PSC)); +} + +/** + * @brief Set the auto-reload value. + * @note The counter is blocked while the auto-reload value is null. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Helper macro @ref __LL_TIM_CALC_ARR can be used to calculate the AutoReload parameter + * @rmtoll ARR ARR LL_TIM_SetAutoReload + * @param TIMx Timer instance + * @param AutoReload between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetAutoReload(TIM_TypeDef *TIMx, uint32_t AutoReload) +{ + WRITE_REG(TIMx->ARR, AutoReload); +} + +/** + * @brief Get the auto-reload value. + * @rmtoll ARR ARR LL_TIM_GetAutoReload + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @param TIMx Timer instance + * @retval Auto-reload value + */ +__STATIC_INLINE uint32_t LL_TIM_GetAutoReload(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->ARR)); +} + +/** + * @brief Set the repetition counter value. + * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a repetition counter. + * @rmtoll RCR REP LL_TIM_SetRepetitionCounter + * @param TIMx Timer instance + * @param RepetitionCounter between Min_Data=0 and Max_Data=255 or 65535 for advanced timer. + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetRepetitionCounter(TIM_TypeDef *TIMx, uint32_t RepetitionCounter) +{ + WRITE_REG(TIMx->RCR, RepetitionCounter); +} + +/** + * @brief Get the repetition counter value. + * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a repetition counter. + * @rmtoll RCR REP LL_TIM_GetRepetitionCounter + * @param TIMx Timer instance + * @retval Repetition counter value + */ +__STATIC_INLINE uint32_t LL_TIM_GetRepetitionCounter(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->RCR)); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Capture_Compare Capture Compare configuration + * @{ + */ +/** + * @brief Enable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. + * @note CCxE, CCxNE and OCxM bits are preloaded, after having been written, + * they are updated only when a commutation event (COM) occurs. + * @note Only on channels that have a complementary output. + * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check + * whether or not a timer instance is able to generate a commutation event. + * @rmtoll CR2 CCPC LL_TIM_CC_EnablePreload + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_EnablePreload(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->CR2, TIM_CR2_CCPC); +} + +/** + * @brief Disable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. + * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check + * whether or not a timer instance is able to generate a commutation event. + * @rmtoll CR2 CCPC LL_TIM_CC_DisablePreload + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_DisablePreload(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->CR2, TIM_CR2_CCPC); +} + +/** + * @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM). + * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check + * whether or not a timer instance is able to generate a commutation event. + * @rmtoll CR2 CCUS LL_TIM_CC_SetUpdate + * @param TIMx Timer instance + * @param CCUpdateSource This parameter can be one of the following values: + * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_ONLY + * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_AND_TRGI + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_SetUpdate(TIM_TypeDef *TIMx, uint32_t CCUpdateSource) +{ + MODIFY_REG(TIMx->CR2, TIM_CR2_CCUS, CCUpdateSource); +} + +/** + * @brief Set the trigger of the capture/compare DMA request. + * @rmtoll CR2 CCDS LL_TIM_CC_SetDMAReqTrigger + * @param TIMx Timer instance + * @param DMAReqTrigger This parameter can be one of the following values: + * @arg @ref LL_TIM_CCDMAREQUEST_CC + * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_SetDMAReqTrigger(TIM_TypeDef *TIMx, uint32_t DMAReqTrigger) +{ + MODIFY_REG(TIMx->CR2, TIM_CR2_CCDS, DMAReqTrigger); +} + +/** + * @brief Get actual trigger of the capture/compare DMA request. + * @rmtoll CR2 CCDS LL_TIM_CC_GetDMAReqTrigger + * @param TIMx Timer instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_CCDMAREQUEST_CC + * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE + */ +__STATIC_INLINE uint32_t LL_TIM_CC_GetDMAReqTrigger(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_BIT(TIMx->CR2, TIM_CR2_CCDS)); +} + +/** + * @brief Set the lock level to freeze the + * configuration of several capture/compare parameters. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * the lock mechanism is supported by a timer instance. + * @rmtoll BDTR LOCK LL_TIM_CC_SetLockLevel + * @param TIMx Timer instance + * @param LockLevel This parameter can be one of the following values: + * @arg @ref LL_TIM_LOCKLEVEL_OFF + * @arg @ref LL_TIM_LOCKLEVEL_1 + * @arg @ref LL_TIM_LOCKLEVEL_2 + * @arg @ref LL_TIM_LOCKLEVEL_3 + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_SetLockLevel(TIM_TypeDef *TIMx, uint32_t LockLevel) +{ + MODIFY_REG(TIMx->BDTR, TIM_BDTR_LOCK, LockLevel); +} + +/** + * @brief Enable capture/compare channels. + * @rmtoll CCER CC1E LL_TIM_CC_EnableChannel\n + * CCER CC1NE LL_TIM_CC_EnableChannel\n + * CCER CC2E LL_TIM_CC_EnableChannel\n + * CCER CC2NE LL_TIM_CC_EnableChannel\n + * CCER CC3E LL_TIM_CC_EnableChannel\n + * CCER CC3NE LL_TIM_CC_EnableChannel\n + * CCER CC4E LL_TIM_CC_EnableChannel + * @param TIMx Timer instance + * @param Channels This parameter can be a combination of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_EnableChannel(TIM_TypeDef *TIMx, uint32_t Channels) +{ + SET_BIT(TIMx->CCER, Channels); +} + +/** + * @brief Disable capture/compare channels. + * @rmtoll CCER CC1E LL_TIM_CC_DisableChannel\n + * CCER CC1NE LL_TIM_CC_DisableChannel\n + * CCER CC2E LL_TIM_CC_DisableChannel\n + * CCER CC2NE LL_TIM_CC_DisableChannel\n + * CCER CC3E LL_TIM_CC_DisableChannel\n + * CCER CC3NE LL_TIM_CC_DisableChannel\n + * CCER CC4E LL_TIM_CC_DisableChannel + * @param TIMx Timer instance + * @param Channels This parameter can be a combination of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_CC_DisableChannel(TIM_TypeDef *TIMx, uint32_t Channels) +{ + CLEAR_BIT(TIMx->CCER, Channels); +} + +/** + * @brief Indicate whether channel(s) is(are) enabled. + * @rmtoll CCER CC1E LL_TIM_CC_IsEnabledChannel\n + * CCER CC1NE LL_TIM_CC_IsEnabledChannel\n + * CCER CC2E LL_TIM_CC_IsEnabledChannel\n + * CCER CC2NE LL_TIM_CC_IsEnabledChannel\n + * CCER CC3E LL_TIM_CC_IsEnabledChannel\n + * CCER CC3NE LL_TIM_CC_IsEnabledChannel\n + * CCER CC4E LL_TIM_CC_IsEnabledChannel + * @param TIMx Timer instance + * @param Channels This parameter can be a combination of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_CC_IsEnabledChannel(TIM_TypeDef *TIMx, uint32_t Channels) +{ + return ((READ_BIT(TIMx->CCER, Channels) == (Channels)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Output_Channel Output channel configuration + * @{ + */ +/** + * @brief Configure an output channel. + * @rmtoll CCMR1 CC1S LL_TIM_OC_ConfigOutput\n + * CCMR1 CC2S LL_TIM_OC_ConfigOutput\n + * CCMR2 CC3S LL_TIM_OC_ConfigOutput\n + * CCMR2 CC4S LL_TIM_OC_ConfigOutput\n + * CCER CC1P LL_TIM_OC_ConfigOutput\n + * CCER CC2P LL_TIM_OC_ConfigOutput\n + * CCER CC3P LL_TIM_OC_ConfigOutput\n + * CCER CC4P LL_TIM_OC_ConfigOutput\n + * CR2 OIS1 LL_TIM_OC_ConfigOutput\n + * CR2 OIS2 LL_TIM_OC_ConfigOutput\n + * CR2 OIS3 LL_TIM_OC_ConfigOutput\n + * CR2 OIS4 LL_TIM_OC_ConfigOutput + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param Configuration This parameter must be a combination of all the following values: + * @arg @ref LL_TIM_OCPOLARITY_HIGH or @ref LL_TIM_OCPOLARITY_LOW + * @arg @ref LL_TIM_OCIDLESTATE_LOW or @ref LL_TIM_OCIDLESTATE_HIGH + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_ConfigOutput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + CLEAR_BIT(*pReg, (TIM_CCMR1_CC1S << SHIFT_TAB_OCxx[iChannel])); + MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), + (Configuration & TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]); + MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), + (Configuration & TIM_CR2_OIS1) << SHIFT_TAB_OISx[iChannel]); +} + +/** + * @brief Define the behavior of the output reference signal OCxREF from which + * OCx and OCxN (when relevant) are derived. + * @rmtoll CCMR1 OC1M LL_TIM_OC_SetMode\n + * CCMR1 OC2M LL_TIM_OC_SetMode\n + * CCMR2 OC3M LL_TIM_OC_SetMode\n + * CCMR2 OC4M LL_TIM_OC_SetMode + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param Mode This parameter can be one of the following values: + * @arg @ref LL_TIM_OCMODE_FROZEN + * @arg @ref LL_TIM_OCMODE_ACTIVE + * @arg @ref LL_TIM_OCMODE_INACTIVE + * @arg @ref LL_TIM_OCMODE_TOGGLE + * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE + * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE + * @arg @ref LL_TIM_OCMODE_PWM1 + * @arg @ref LL_TIM_OCMODE_PWM2 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetMode(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Mode) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + MODIFY_REG(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel]), Mode << SHIFT_TAB_OCxx[iChannel]); +} + +/** + * @brief Get the output compare mode of an output channel. + * @rmtoll CCMR1 OC1M LL_TIM_OC_GetMode\n + * CCMR1 OC2M LL_TIM_OC_GetMode\n + * CCMR2 OC3M LL_TIM_OC_GetMode\n + * CCMR2 OC4M LL_TIM_OC_GetMode + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_OCMODE_FROZEN + * @arg @ref LL_TIM_OCMODE_ACTIVE + * @arg @ref LL_TIM_OCMODE_INACTIVE + * @arg @ref LL_TIM_OCMODE_TOGGLE + * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE + * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE + * @arg @ref LL_TIM_OCMODE_PWM1 + * @arg @ref LL_TIM_OCMODE_PWM2 + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetMode(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + return (READ_BIT(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel])) >> SHIFT_TAB_OCxx[iChannel]); +} + +/** + * @brief Set the polarity of an output channel. + * @rmtoll CCER CC1P LL_TIM_OC_SetPolarity\n + * CCER CC1NP LL_TIM_OC_SetPolarity\n + * CCER CC2P LL_TIM_OC_SetPolarity\n + * CCER CC2NP LL_TIM_OC_SetPolarity\n + * CCER CC3P LL_TIM_OC_SetPolarity\n + * CCER CC3NP LL_TIM_OC_SetPolarity\n + * CCER CC4P LL_TIM_OC_SetPolarity + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param Polarity This parameter can be one of the following values: + * @arg @ref LL_TIM_OCPOLARITY_HIGH + * @arg @ref LL_TIM_OCPOLARITY_LOW + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Polarity) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), Polarity << SHIFT_TAB_CCxP[iChannel]); +} + +/** + * @brief Get the polarity of an output channel. + * @rmtoll CCER CC1P LL_TIM_OC_GetPolarity\n + * CCER CC1NP LL_TIM_OC_GetPolarity\n + * CCER CC2P LL_TIM_OC_GetPolarity\n + * CCER CC2NP LL_TIM_OC_GetPolarity\n + * CCER CC3P LL_TIM_OC_GetPolarity\n + * CCER CC3NP LL_TIM_OC_GetPolarity\n + * CCER CC4P LL_TIM_OC_GetPolarity + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_OCPOLARITY_HIGH + * @arg @ref LL_TIM_OCPOLARITY_LOW + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + return (READ_BIT(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel])) >> SHIFT_TAB_CCxP[iChannel]); +} + +/** + * @brief Set the IDLE state of an output channel + * @note This function is significant only for the timer instances + * supporting the break feature. Macro IS_TIM_BREAK_INSTANCE(TIMx) + * can be used to check whether or not a timer instance provides + * a break input. + * @rmtoll CR2 OIS1 LL_TIM_OC_SetIdleState\n + * CR2 OIS1N LL_TIM_OC_SetIdleState\n + * CR2 OIS2 LL_TIM_OC_SetIdleState\n + * CR2 OIS2N LL_TIM_OC_SetIdleState\n + * CR2 OIS3 LL_TIM_OC_SetIdleState\n + * CR2 OIS3N LL_TIM_OC_SetIdleState\n + * CR2 OIS4 LL_TIM_OC_SetIdleState + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param IdleState This parameter can be one of the following values: + * @arg @ref LL_TIM_OCIDLESTATE_LOW + * @arg @ref LL_TIM_OCIDLESTATE_HIGH + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetIdleState(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t IdleState) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), IdleState << SHIFT_TAB_OISx[iChannel]); +} + +/** + * @brief Get the IDLE state of an output channel + * @rmtoll CR2 OIS1 LL_TIM_OC_GetIdleState\n + * CR2 OIS1N LL_TIM_OC_GetIdleState\n + * CR2 OIS2 LL_TIM_OC_GetIdleState\n + * CR2 OIS2N LL_TIM_OC_GetIdleState\n + * CR2 OIS3 LL_TIM_OC_GetIdleState\n + * CR2 OIS3N LL_TIM_OC_GetIdleState\n + * CR2 OIS4 LL_TIM_OC_GetIdleState + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH1N + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH2N + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH3N + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_OCIDLESTATE_LOW + * @arg @ref LL_TIM_OCIDLESTATE_HIGH + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetIdleState(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + return (READ_BIT(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel])) >> SHIFT_TAB_OISx[iChannel]); +} + +/** + * @brief Enable fast mode for the output channel. + * @note Acts only if the channel is configured in PWM1 or PWM2 mode. + * @rmtoll CCMR1 OC1FE LL_TIM_OC_EnableFast\n + * CCMR1 OC2FE LL_TIM_OC_EnableFast\n + * CCMR2 OC3FE LL_TIM_OC_EnableFast\n + * CCMR2 OC4FE LL_TIM_OC_EnableFast + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_EnableFast(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + SET_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); + +} + +/** + * @brief Disable fast mode for the output channel. + * @rmtoll CCMR1 OC1FE LL_TIM_OC_DisableFast\n + * CCMR1 OC2FE LL_TIM_OC_DisableFast\n + * CCMR2 OC3FE LL_TIM_OC_DisableFast\n + * CCMR2 OC4FE LL_TIM_OC_DisableFast + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_DisableFast(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + CLEAR_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); + +} + +/** + * @brief Indicates whether fast mode is enabled for the output channel. + * @rmtoll CCMR1 OC1FE LL_TIM_OC_IsEnabledFast\n + * CCMR1 OC2FE LL_TIM_OC_IsEnabledFast\n + * CCMR2 OC3FE LL_TIM_OC_IsEnabledFast\n + * CCMR2 OC4FE LL_TIM_OC_IsEnabledFast\n + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledFast(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + uint32_t bitfield = TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel]; + return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); +} + +/** + * @brief Enable compare register (TIMx_CCRx) preload for the output channel. + * @rmtoll CCMR1 OC1PE LL_TIM_OC_EnablePreload\n + * CCMR1 OC2PE LL_TIM_OC_EnablePreload\n + * CCMR2 OC3PE LL_TIM_OC_EnablePreload\n + * CCMR2 OC4PE LL_TIM_OC_EnablePreload + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_EnablePreload(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + SET_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); +} + +/** + * @brief Disable compare register (TIMx_CCRx) preload for the output channel. + * @rmtoll CCMR1 OC1PE LL_TIM_OC_DisablePreload\n + * CCMR1 OC2PE LL_TIM_OC_DisablePreload\n + * CCMR2 OC3PE LL_TIM_OC_DisablePreload\n + * CCMR2 OC4PE LL_TIM_OC_DisablePreload + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_DisablePreload(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + CLEAR_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); +} + +/** + * @brief Indicates whether compare register (TIMx_CCRx) preload is enabled for the output channel. + * @rmtoll CCMR1 OC1PE LL_TIM_OC_IsEnabledPreload\n + * CCMR1 OC2PE LL_TIM_OC_IsEnabledPreload\n + * CCMR2 OC3PE LL_TIM_OC_IsEnabledPreload\n + * CCMR2 OC4PE LL_TIM_OC_IsEnabledPreload\n + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledPreload(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + uint32_t bitfield = TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel]; + return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); +} + +/** + * @brief Enable clearing the output channel on an external event. + * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. + * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether + * or not a timer instance can clear the OCxREF signal on an external event. + * @rmtoll CCMR1 OC1CE LL_TIM_OC_EnableClear\n + * CCMR1 OC2CE LL_TIM_OC_EnableClear\n + * CCMR2 OC3CE LL_TIM_OC_EnableClear\n + * CCMR2 OC4CE LL_TIM_OC_EnableClear + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_EnableClear(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + SET_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); +} + +/** + * @brief Disable clearing the output channel on an external event. + * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether + * or not a timer instance can clear the OCxREF signal on an external event. + * @rmtoll CCMR1 OC1CE LL_TIM_OC_DisableClear\n + * CCMR1 OC2CE LL_TIM_OC_DisableClear\n + * CCMR2 OC3CE LL_TIM_OC_DisableClear\n + * CCMR2 OC4CE LL_TIM_OC_DisableClear + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_DisableClear(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + CLEAR_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); +} + +/** + * @brief Indicates clearing the output channel on an external event is enabled for the output channel. + * @note This function enables clearing the output channel on an external event. + * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. + * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether + * or not a timer instance can clear the OCxREF signal on an external event. + * @rmtoll CCMR1 OC1CE LL_TIM_OC_IsEnabledClear\n + * CCMR1 OC2CE LL_TIM_OC_IsEnabledClear\n + * CCMR2 OC3CE LL_TIM_OC_IsEnabledClear\n + * CCMR2 OC4CE LL_TIM_OC_IsEnabledClear\n + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledClear(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + uint32_t bitfield = TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel]; + return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); +} + +/** + * @brief Set the dead-time delay (delay inserted between the rising edge of the OCxREF signal and the rising edge of + * the Ocx and OCxN signals). + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * dead-time insertion feature is supported by a timer instance. + * @note Helper macro @ref __LL_TIM_CALC_DEADTIME can be used to calculate the DeadTime parameter + * @rmtoll BDTR DTG LL_TIM_OC_SetDeadTime + * @param TIMx Timer instance + * @param DeadTime between Min_Data=0 and Max_Data=255 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetDeadTime(TIM_TypeDef *TIMx, uint32_t DeadTime) +{ + MODIFY_REG(TIMx->BDTR, TIM_BDTR_DTG, DeadTime); +} + +/** + * @brief Set compare value for output channel 1 (TIMx_CCR1). + * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not + * output channel 1 is supported by a timer instance. + * @rmtoll CCR1 CCR1 LL_TIM_OC_SetCompareCH1 + * @param TIMx Timer instance + * @param CompareValue between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetCompareCH1(TIM_TypeDef *TIMx, uint32_t CompareValue) +{ + WRITE_REG(TIMx->CCR1, CompareValue); +} + +/** + * @brief Set compare value for output channel 2 (TIMx_CCR2). + * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not + * output channel 2 is supported by a timer instance. + * @rmtoll CCR2 CCR2 LL_TIM_OC_SetCompareCH2 + * @param TIMx Timer instance + * @param CompareValue between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetCompareCH2(TIM_TypeDef *TIMx, uint32_t CompareValue) +{ + WRITE_REG(TIMx->CCR2, CompareValue); +} + +/** + * @brief Set compare value for output channel 3 (TIMx_CCR3). + * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not + * output channel is supported by a timer instance. + * @rmtoll CCR3 CCR3 LL_TIM_OC_SetCompareCH3 + * @param TIMx Timer instance + * @param CompareValue between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetCompareCH3(TIM_TypeDef *TIMx, uint32_t CompareValue) +{ + WRITE_REG(TIMx->CCR3, CompareValue); +} + +/** + * @brief Set compare value for output channel 4 (TIMx_CCR4). + * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not + * output channel 4 is supported by a timer instance. + * @rmtoll CCR4 CCR4 LL_TIM_OC_SetCompareCH4 + * @param TIMx Timer instance + * @param CompareValue between Min_Data=0 and Max_Data=65535 + * @retval None + */ +__STATIC_INLINE void LL_TIM_OC_SetCompareCH4(TIM_TypeDef *TIMx, uint32_t CompareValue) +{ + WRITE_REG(TIMx->CCR4, CompareValue); +} + +/** + * @brief Get compare value (TIMx_CCR1) set for output channel 1. + * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not + * output channel 1 is supported by a timer instance. + * @rmtoll CCR1 CCR1 LL_TIM_OC_GetCompareCH1 + * @param TIMx Timer instance + * @retval CompareValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH1(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR1)); +} + +/** + * @brief Get compare value (TIMx_CCR2) set for output channel 2. + * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not + * output channel 2 is supported by a timer instance. + * @rmtoll CCR2 CCR2 LL_TIM_OC_GetCompareCH2 + * @param TIMx Timer instance + * @retval CompareValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH2(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR2)); +} + +/** + * @brief Get compare value (TIMx_CCR3) set for output channel 3. + * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not + * output channel 3 is supported by a timer instance. + * @rmtoll CCR3 CCR3 LL_TIM_OC_GetCompareCH3 + * @param TIMx Timer instance + * @retval CompareValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH3(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR3)); +} + +/** + * @brief Get compare value (TIMx_CCR4) set for output channel 4. + * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not + * output channel 4 is supported by a timer instance. + * @rmtoll CCR4 CCR4 LL_TIM_OC_GetCompareCH4 + * @param TIMx Timer instance + * @retval CompareValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH4(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR4)); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Input_Channel Input channel configuration + * @{ + */ +/** + * @brief Configure input channel. + * @rmtoll CCMR1 CC1S LL_TIM_IC_Config\n + * CCMR1 IC1PSC LL_TIM_IC_Config\n + * CCMR1 IC1F LL_TIM_IC_Config\n + * CCMR1 CC2S LL_TIM_IC_Config\n + * CCMR1 IC2PSC LL_TIM_IC_Config\n + * CCMR1 IC2F LL_TIM_IC_Config\n + * CCMR2 CC3S LL_TIM_IC_Config\n + * CCMR2 IC3PSC LL_TIM_IC_Config\n + * CCMR2 IC3F LL_TIM_IC_Config\n + * CCMR2 CC4S LL_TIM_IC_Config\n + * CCMR2 IC4PSC LL_TIM_IC_Config\n + * CCMR2 IC4F LL_TIM_IC_Config\n + * CCER CC1P LL_TIM_IC_Config\n + * CCER CC1NP LL_TIM_IC_Config\n + * CCER CC2P LL_TIM_IC_Config\n + * CCER CC2NP LL_TIM_IC_Config\n + * CCER CC3P LL_TIM_IC_Config\n + * CCER CC3NP LL_TIM_IC_Config\n + * CCER CC4P LL_TIM_IC_Config\n + * CCER CC4NP LL_TIM_IC_Config + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param Configuration This parameter must be a combination of all the following values: + * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI or @ref LL_TIM_ACTIVEINPUT_INDIRECTTI or @ref LL_TIM_ACTIVEINPUT_TRC + * @arg @ref LL_TIM_ICPSC_DIV1 or ... or @ref LL_TIM_ICPSC_DIV8 + * @arg @ref LL_TIM_IC_FILTER_FDIV1 or ... or @ref LL_TIM_IC_FILTER_FDIV32_N8 + * @arg @ref LL_TIM_IC_POLARITY_RISING or @ref LL_TIM_IC_POLARITY_FALLING or @ref LL_TIM_IC_POLARITY_BOTHEDGE + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_Config(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), + ((Configuration >> 16U) & (TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S)) \ + << SHIFT_TAB_ICxx[iChannel]); + MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), + (Configuration & (TIM_CCER_CC1NP | TIM_CCER_CC1P)) << SHIFT_TAB_CCxP[iChannel]); +} + +/** + * @brief Set the active input. + * @rmtoll CCMR1 CC1S LL_TIM_IC_SetActiveInput\n + * CCMR1 CC2S LL_TIM_IC_SetActiveInput\n + * CCMR2 CC3S LL_TIM_IC_SetActiveInput\n + * CCMR2 CC4S LL_TIM_IC_SetActiveInput + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param ICActiveInput This parameter can be one of the following values: + * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI + * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI + * @arg @ref LL_TIM_ACTIVEINPUT_TRC + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_SetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICActiveInput) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + MODIFY_REG(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), (ICActiveInput >> 16U) << SHIFT_TAB_ICxx[iChannel]); +} + +/** + * @brief Get the current active input. + * @rmtoll CCMR1 CC1S LL_TIM_IC_GetActiveInput\n + * CCMR1 CC2S LL_TIM_IC_GetActiveInput\n + * CCMR2 CC3S LL_TIM_IC_GetActiveInput\n + * CCMR2 CC4S LL_TIM_IC_GetActiveInput + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI + * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI + * @arg @ref LL_TIM_ACTIVEINPUT_TRC + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + return ((READ_BIT(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); +} + +/** + * @brief Set the prescaler of input channel. + * @rmtoll CCMR1 IC1PSC LL_TIM_IC_SetPrescaler\n + * CCMR1 IC2PSC LL_TIM_IC_SetPrescaler\n + * CCMR2 IC3PSC LL_TIM_IC_SetPrescaler\n + * CCMR2 IC4PSC LL_TIM_IC_SetPrescaler + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param ICPrescaler This parameter can be one of the following values: + * @arg @ref LL_TIM_ICPSC_DIV1 + * @arg @ref LL_TIM_ICPSC_DIV2 + * @arg @ref LL_TIM_ICPSC_DIV4 + * @arg @ref LL_TIM_ICPSC_DIV8 + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPrescaler) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + MODIFY_REG(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel]), (ICPrescaler >> 16U) << SHIFT_TAB_ICxx[iChannel]); +} + +/** + * @brief Get the current prescaler value acting on an input channel. + * @rmtoll CCMR1 IC1PSC LL_TIM_IC_GetPrescaler\n + * CCMR1 IC2PSC LL_TIM_IC_GetPrescaler\n + * CCMR2 IC3PSC LL_TIM_IC_GetPrescaler\n + * CCMR2 IC4PSC LL_TIM_IC_GetPrescaler + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_ICPSC_DIV1 + * @arg @ref LL_TIM_ICPSC_DIV2 + * @arg @ref LL_TIM_ICPSC_DIV4 + * @arg @ref LL_TIM_ICPSC_DIV8 + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); +} + +/** + * @brief Set the input filter duration. + * @rmtoll CCMR1 IC1F LL_TIM_IC_SetFilter\n + * CCMR1 IC2F LL_TIM_IC_SetFilter\n + * CCMR2 IC3F LL_TIM_IC_SetFilter\n + * CCMR2 IC4F LL_TIM_IC_SetFilter + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param ICFilter This parameter can be one of the following values: + * @arg @ref LL_TIM_IC_FILTER_FDIV1 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_SetFilter(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICFilter) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel]), (ICFilter >> 16U) << SHIFT_TAB_ICxx[iChannel]); +} + +/** + * @brief Get the input filter duration. + * @rmtoll CCMR1 IC1F LL_TIM_IC_GetFilter\n + * CCMR1 IC2F LL_TIM_IC_GetFilter\n + * CCMR2 IC3F LL_TIM_IC_GetFilter\n + * CCMR2 IC4F LL_TIM_IC_GetFilter + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_IC_FILTER_FDIV1 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 + * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 + * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetFilter(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); + return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); +} + +/** + * @brief Set the input channel polarity. + * @rmtoll CCER CC1P LL_TIM_IC_SetPolarity\n + * CCER CC1NP LL_TIM_IC_SetPolarity\n + * CCER CC2P LL_TIM_IC_SetPolarity\n + * CCER CC2NP LL_TIM_IC_SetPolarity\n + * CCER CC3P LL_TIM_IC_SetPolarity\n + * CCER CC3NP LL_TIM_IC_SetPolarity\n + * CCER CC4P LL_TIM_IC_SetPolarity\n + * CCER CC4NP LL_TIM_IC_SetPolarity + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param ICPolarity This parameter can be one of the following values: + * @arg @ref LL_TIM_IC_POLARITY_RISING + * @arg @ref LL_TIM_IC_POLARITY_FALLING + * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPolarity) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), + ICPolarity << SHIFT_TAB_CCxP[iChannel]); +} + +/** + * @brief Get the current input channel polarity. + * @rmtoll CCER CC1P LL_TIM_IC_GetPolarity\n + * CCER CC1NP LL_TIM_IC_GetPolarity\n + * CCER CC2P LL_TIM_IC_GetPolarity\n + * CCER CC2NP LL_TIM_IC_GetPolarity\n + * CCER CC3P LL_TIM_IC_GetPolarity\n + * CCER CC3NP LL_TIM_IC_GetPolarity\n + * CCER CC4P LL_TIM_IC_GetPolarity\n + * CCER CC4NP LL_TIM_IC_GetPolarity + * @param TIMx Timer instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @retval Returned value can be one of the following values: + * @arg @ref LL_TIM_IC_POLARITY_RISING + * @arg @ref LL_TIM_IC_POLARITY_FALLING + * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) +{ + uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); + return (READ_BIT(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel])) >> + SHIFT_TAB_CCxP[iChannel]); +} + +/** + * @brief Connect the TIMx_CH1, CH2 and CH3 pins to the TI1 input (XOR combination). + * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides an XOR input. + * @rmtoll CR2 TI1S LL_TIM_IC_EnableXORCombination + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_EnableXORCombination(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->CR2, TIM_CR2_TI1S); +} + +/** + * @brief Disconnect the TIMx_CH1, CH2 and CH3 pins from the TI1 input. + * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides an XOR input. + * @rmtoll CR2 TI1S LL_TIM_IC_DisableXORCombination + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_IC_DisableXORCombination(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->CR2, TIM_CR2_TI1S); +} + +/** + * @brief Indicates whether the TIMx_CH1, CH2 and CH3 pins are connectected to the TI1 input. + * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides an XOR input. + * @rmtoll CR2 TI1S LL_TIM_IC_IsEnabledXORCombination + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IC_IsEnabledXORCombination(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->CR2, TIM_CR2_TI1S) == (TIM_CR2_TI1S)) ? 1UL : 0UL); +} + +/** + * @brief Get captured value for input channel 1. + * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not + * input channel 1 is supported by a timer instance. + * @rmtoll CCR1 CCR1 LL_TIM_IC_GetCaptureCH1 + * @param TIMx Timer instance + * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH1(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR1)); +} + +/** + * @brief Get captured value for input channel 2. + * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not + * input channel 2 is supported by a timer instance. + * @rmtoll CCR2 CCR2 LL_TIM_IC_GetCaptureCH2 + * @param TIMx Timer instance + * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH2(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR2)); +} + +/** + * @brief Get captured value for input channel 3. + * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not + * input channel 3 is supported by a timer instance. + * @rmtoll CCR3 CCR3 LL_TIM_IC_GetCaptureCH3 + * @param TIMx Timer instance + * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH3(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR3)); +} + +/** + * @brief Get captured value for input channel 4. + * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. + * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports a 32 bits counter. + * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not + * input channel 4 is supported by a timer instance. + * @rmtoll CCR4 CCR4 LL_TIM_IC_GetCaptureCH4 + * @param TIMx Timer instance + * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) + */ +__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH4(TIM_TypeDef *TIMx) +{ + return (uint32_t)(READ_REG(TIMx->CCR4)); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Clock_Selection Counter clock selection + * @{ + */ +/** + * @brief Enable external clock mode 2. + * @note When external clock mode 2 is enabled the counter is clocked by any active edge on the ETRF signal. + * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports external clock mode2. + * @rmtoll SMCR ECE LL_TIM_EnableExternalClock + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableExternalClock(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->SMCR, TIM_SMCR_ECE); +} + +/** + * @brief Disable external clock mode 2. + * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports external clock mode2. + * @rmtoll SMCR ECE LL_TIM_DisableExternalClock + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableExternalClock(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->SMCR, TIM_SMCR_ECE); +} + +/** + * @brief Indicate whether external clock mode 2 is enabled. + * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports external clock mode2. + * @rmtoll SMCR ECE LL_TIM_IsEnabledExternalClock + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledExternalClock(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SMCR, TIM_SMCR_ECE) == (TIM_SMCR_ECE)) ? 1UL : 0UL); +} + +/** + * @brief Set the clock source of the counter clock. + * @note when selected clock source is external clock mode 1, the timer input + * the external clock is applied is selected by calling the @ref LL_TIM_SetTriggerInput() + * function. This timer input must be configured by calling + * the @ref LL_TIM_IC_Config() function. + * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports external clock mode1. + * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports external clock mode2. + * @rmtoll SMCR SMS LL_TIM_SetClockSource\n + * SMCR ECE LL_TIM_SetClockSource + * @param TIMx Timer instance + * @param ClockSource This parameter can be one of the following values: + * @arg @ref LL_TIM_CLOCKSOURCE_INTERNAL + * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE1 + * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE2 + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetClockSource(TIM_TypeDef *TIMx, uint32_t ClockSource) +{ + MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS | TIM_SMCR_ECE, ClockSource); +} + +/** + * @brief Set the encoder interface mode. + * @note Macro IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx) can be used to check + * whether or not a timer instance supports the encoder mode. + * @rmtoll SMCR SMS LL_TIM_SetEncoderMode + * @param TIMx Timer instance + * @param EncoderMode This parameter can be one of the following values: + * @arg @ref LL_TIM_ENCODERMODE_X2_TI1 + * @arg @ref LL_TIM_ENCODERMODE_X2_TI2 + * @arg @ref LL_TIM_ENCODERMODE_X4_TI12 + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetEncoderMode(TIM_TypeDef *TIMx, uint32_t EncoderMode) +{ + MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, EncoderMode); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Timer_Synchronization Timer synchronisation configuration + * @{ + */ +/** + * @brief Set the trigger output (TRGO) used for timer synchronization . + * @note Macro IS_TIM_MASTER_INSTANCE(TIMx) can be used to check + * whether or not a timer instance can operate as a master timer. + * @rmtoll CR2 MMS LL_TIM_SetTriggerOutput + * @param TIMx Timer instance + * @param TimerSynchronization This parameter can be one of the following values: + * @arg @ref LL_TIM_TRGO_RESET + * @arg @ref LL_TIM_TRGO_ENABLE + * @arg @ref LL_TIM_TRGO_UPDATE + * @arg @ref LL_TIM_TRGO_CC1IF + * @arg @ref LL_TIM_TRGO_OC1REF + * @arg @ref LL_TIM_TRGO_OC2REF + * @arg @ref LL_TIM_TRGO_OC3REF + * @arg @ref LL_TIM_TRGO_OC4REF + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetTriggerOutput(TIM_TypeDef *TIMx, uint32_t TimerSynchronization) +{ + MODIFY_REG(TIMx->CR2, TIM_CR2_MMS, TimerSynchronization); +} + +/** + * @brief Set the synchronization mode of a slave timer. + * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not + * a timer instance can operate as a slave timer. + * @rmtoll SMCR SMS LL_TIM_SetSlaveMode + * @param TIMx Timer instance + * @param SlaveMode This parameter can be one of the following values: + * @arg @ref LL_TIM_SLAVEMODE_DISABLED + * @arg @ref LL_TIM_SLAVEMODE_RESET + * @arg @ref LL_TIM_SLAVEMODE_GATED + * @arg @ref LL_TIM_SLAVEMODE_TRIGGER + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetSlaveMode(TIM_TypeDef *TIMx, uint32_t SlaveMode) +{ + MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, SlaveMode); +} + +/** + * @brief Set the selects the trigger input to be used to synchronize the counter. + * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not + * a timer instance can operate as a slave timer. + * @rmtoll SMCR TS LL_TIM_SetTriggerInput + * @param TIMx Timer instance + * @param TriggerInput This parameter can be one of the following values: + * @arg @ref LL_TIM_TS_ITR0 + * @arg @ref LL_TIM_TS_ITR1 + * @arg @ref LL_TIM_TS_ITR2 + * @arg @ref LL_TIM_TS_ITR3 + * @arg @ref LL_TIM_TS_TI1F_ED + * @arg @ref LL_TIM_TS_TI1FP1 + * @arg @ref LL_TIM_TS_TI2FP2 + * @arg @ref LL_TIM_TS_ETRF + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetTriggerInput(TIM_TypeDef *TIMx, uint32_t TriggerInput) +{ + MODIFY_REG(TIMx->SMCR, TIM_SMCR_TS, TriggerInput); +} + +/** + * @brief Enable the Master/Slave mode. + * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not + * a timer instance can operate as a slave timer. + * @rmtoll SMCR MSM LL_TIM_EnableMasterSlaveMode + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableMasterSlaveMode(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->SMCR, TIM_SMCR_MSM); +} + +/** + * @brief Disable the Master/Slave mode. + * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not + * a timer instance can operate as a slave timer. + * @rmtoll SMCR MSM LL_TIM_DisableMasterSlaveMode + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableMasterSlaveMode(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->SMCR, TIM_SMCR_MSM); +} + +/** + * @brief Indicates whether the Master/Slave mode is enabled. + * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not + * a timer instance can operate as a slave timer. + * @rmtoll SMCR MSM LL_TIM_IsEnabledMasterSlaveMode + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledMasterSlaveMode(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SMCR, TIM_SMCR_MSM) == (TIM_SMCR_MSM)) ? 1UL : 0UL); +} + +/** + * @brief Configure the external trigger (ETR) input. + * @note Macro IS_TIM_ETR_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides an external trigger input. + * @rmtoll SMCR ETP LL_TIM_ConfigETR\n + * SMCR ETPS LL_TIM_ConfigETR\n + * SMCR ETF LL_TIM_ConfigETR + * @param TIMx Timer instance + * @param ETRPolarity This parameter can be one of the following values: + * @arg @ref LL_TIM_ETR_POLARITY_NONINVERTED + * @arg @ref LL_TIM_ETR_POLARITY_INVERTED + * @param ETRPrescaler This parameter can be one of the following values: + * @arg @ref LL_TIM_ETR_PRESCALER_DIV1 + * @arg @ref LL_TIM_ETR_PRESCALER_DIV2 + * @arg @ref LL_TIM_ETR_PRESCALER_DIV4 + * @arg @ref LL_TIM_ETR_PRESCALER_DIV8 + * @param ETRFilter This parameter can be one of the following values: + * @arg @ref LL_TIM_ETR_FILTER_FDIV1 + * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N2 + * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N4 + * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N8 + * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N6 + * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N8 + * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N6 + * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N8 + * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N6 + * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N8 + * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N5 + * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N6 + * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N8 + * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N5 + * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N6 + * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N8 + * @retval None + */ +__STATIC_INLINE void LL_TIM_ConfigETR(TIM_TypeDef *TIMx, uint32_t ETRPolarity, uint32_t ETRPrescaler, + uint32_t ETRFilter) +{ + MODIFY_REG(TIMx->SMCR, TIM_SMCR_ETP | TIM_SMCR_ETPS | TIM_SMCR_ETF, ETRPolarity | ETRPrescaler | ETRFilter); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Break_Function Break function configuration + * @{ + */ +/** + * @brief Enable the break function. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR BKE LL_TIM_EnableBRK + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableBRK(TIM_TypeDef *TIMx) +{ + __IO uint32_t tmpreg; + SET_BIT(TIMx->BDTR, TIM_BDTR_BKE); + /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ + tmpreg = READ_REG(TIMx->BDTR); + (void)(tmpreg); +} + +/** + * @brief Disable the break function. + * @rmtoll BDTR BKE LL_TIM_DisableBRK + * @param TIMx Timer instance + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableBRK(TIM_TypeDef *TIMx) +{ + __IO uint32_t tmpreg; + CLEAR_BIT(TIMx->BDTR, TIM_BDTR_BKE); + /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ + tmpreg = READ_REG(TIMx->BDTR); + (void)(tmpreg); +} + +/** + * @brief Configure the break input. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR BKP LL_TIM_ConfigBRK + * @param TIMx Timer instance + * @param BreakPolarity This parameter can be one of the following values: + * @arg @ref LL_TIM_BREAK_POLARITY_LOW + * @arg @ref LL_TIM_BREAK_POLARITY_HIGH + * @retval None + */ +__STATIC_INLINE void LL_TIM_ConfigBRK(TIM_TypeDef *TIMx, uint32_t BreakPolarity) +{ + __IO uint32_t tmpreg; + MODIFY_REG(TIMx->BDTR, TIM_BDTR_BKP, BreakPolarity); + /* Note: Any write operation to BKP bit takes a delay of 1 APB clock cycle to become effective. */ + tmpreg = READ_REG(TIMx->BDTR); + (void)(tmpreg); +} + +/** + * @brief Select the outputs off state (enabled v.s. disabled) in Idle and Run modes. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR OSSI LL_TIM_SetOffStates\n + * BDTR OSSR LL_TIM_SetOffStates + * @param TIMx Timer instance + * @param OffStateIdle This parameter can be one of the following values: + * @arg @ref LL_TIM_OSSI_DISABLE + * @arg @ref LL_TIM_OSSI_ENABLE + * @param OffStateRun This parameter can be one of the following values: + * @arg @ref LL_TIM_OSSR_DISABLE + * @arg @ref LL_TIM_OSSR_ENABLE + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetOffStates(TIM_TypeDef *TIMx, uint32_t OffStateIdle, uint32_t OffStateRun) +{ + MODIFY_REG(TIMx->BDTR, TIM_BDTR_OSSI | TIM_BDTR_OSSR, OffStateIdle | OffStateRun); +} + +/** + * @brief Enable automatic output (MOE can be set by software or automatically when a break input is active). + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR AOE LL_TIM_EnableAutomaticOutput + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableAutomaticOutput(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->BDTR, TIM_BDTR_AOE); +} + +/** + * @brief Disable automatic output (MOE can be set only by software). + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR AOE LL_TIM_DisableAutomaticOutput + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableAutomaticOutput(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->BDTR, TIM_BDTR_AOE); +} + +/** + * @brief Indicate whether automatic output is enabled. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR AOE LL_TIM_IsEnabledAutomaticOutput + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledAutomaticOutput(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->BDTR, TIM_BDTR_AOE) == (TIM_BDTR_AOE)) ? 1UL : 0UL); +} + +/** + * @brief Enable the outputs (set the MOE bit in TIMx_BDTR register). + * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by + * software and is reset in case of break or break2 event + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR MOE LL_TIM_EnableAllOutputs + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableAllOutputs(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->BDTR, TIM_BDTR_MOE); +} + +/** + * @brief Disable the outputs (reset the MOE bit in TIMx_BDTR register). + * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by + * software and is reset in case of break or break2 event. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR MOE LL_TIM_DisableAllOutputs + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableAllOutputs(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->BDTR, TIM_BDTR_MOE); +} + +/** + * @brief Indicates whether outputs are enabled. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @rmtoll BDTR MOE LL_TIM_IsEnabledAllOutputs + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledAllOutputs(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->BDTR, TIM_BDTR_MOE) == (TIM_BDTR_MOE)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_DMA_Burst_Mode DMA burst mode configuration + * @{ + */ +/** + * @brief Configures the timer DMA burst feature. + * @note Macro IS_TIM_DMABURST_INSTANCE(TIMx) can be used to check whether or + * not a timer instance supports the DMA burst mode. + * @rmtoll DCR DBL LL_TIM_ConfigDMABurst\n + * DCR DBA LL_TIM_ConfigDMABurst + * @param TIMx Timer instance + * @param DMABurstBaseAddress This parameter can be one of the following values: + * @arg @ref LL_TIM_DMABURST_BASEADDR_CR1 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CR2 + * @arg @ref LL_TIM_DMABURST_BASEADDR_SMCR + * @arg @ref LL_TIM_DMABURST_BASEADDR_DIER + * @arg @ref LL_TIM_DMABURST_BASEADDR_SR + * @arg @ref LL_TIM_DMABURST_BASEADDR_EGR + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR1 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR2 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCER + * @arg @ref LL_TIM_DMABURST_BASEADDR_CNT + * @arg @ref LL_TIM_DMABURST_BASEADDR_PSC + * @arg @ref LL_TIM_DMABURST_BASEADDR_ARR + * @arg @ref LL_TIM_DMABURST_BASEADDR_RCR + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR1 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR2 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR3 + * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR4 + * @arg @ref LL_TIM_DMABURST_BASEADDR_BDTR + * @param DMABurstLength This parameter can be one of the following values: + * @arg @ref LL_TIM_DMABURST_LENGTH_1TRANSFER + * @arg @ref LL_TIM_DMABURST_LENGTH_2TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_3TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_4TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_5TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_6TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_7TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_8TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_9TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_10TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_11TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_12TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_13TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_14TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_15TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_16TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_17TRANSFERS + * @arg @ref LL_TIM_DMABURST_LENGTH_18TRANSFERS + * @retval None + */ +__STATIC_INLINE void LL_TIM_ConfigDMABurst(TIM_TypeDef *TIMx, uint32_t DMABurstBaseAddress, uint32_t DMABurstLength) +{ + MODIFY_REG(TIMx->DCR, (TIM_DCR_DBL | TIM_DCR_DBA), (DMABurstBaseAddress | DMABurstLength)); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_Timer_Inputs_Remapping Timer input remapping + * @{ + */ +/** + * @brief Remap TIM inputs (input channel, internal/external triggers). + * @note Macro IS_TIM_REMAP_INSTANCE(TIMx) can be used to check whether or not + * a some timer inputs can be remapped. + * @rmtoll TIM1_OR ITR2_RMP LL_TIM_SetRemap\n + * TIM2_OR ITR1_RMP LL_TIM_SetRemap\n + * TIM5_OR ITR1_RMP LL_TIM_SetRemap\n + * TIM5_OR TI4_RMP LL_TIM_SetRemap\n + * TIM9_OR ITR1_RMP LL_TIM_SetRemap\n + * TIM11_OR TI1_RMP LL_TIM_SetRemap\n + * LPTIM1_OR OR LL_TIM_SetRemap + * @param TIMx Timer instance + * @param Remap Remap param depends on the TIMx. Description available only + * in CHM version of the User Manual (not in .pdf). + * Otherwise see Reference Manual description of OR registers. + * + * Below description summarizes "Timer Instance" and "Remap" param combinations: + * + * TIM1: one of the following values + * + * ITR2_RMP can be one of the following values + * @arg @ref LL_TIM_TIM1_ITR2_RMP_TIM3_TRGO (*) + * @arg @ref LL_TIM_TIM1_ITR2_RMP_LPTIM (*) + * + * TIM2: one of the following values + * + * ITR1_RMP can be one of the following values + * @arg @ref LL_TIM_TIM2_ITR1_RMP_TIM8_TRGO + * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_FS_SOF + * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_HS_SOF + * + * TIM5: one of the following values + * + * @arg @ref LL_TIM_TIM5_TI4_RMP_GPIO + * @arg @ref LL_TIM_TIM5_TI4_RMP_LSI + * @arg @ref LL_TIM_TIM5_TI4_RMP_LSE + * @arg @ref LL_TIM_TIM5_TI4_RMP_RTC + * @arg @ref LL_TIM_TIM5_ITR1_RMP_TIM3_TRGO (*) + * @arg @ref LL_TIM_TIM5_ITR1_RMP_LPTIM (*) + * + * TIM9: one of the following values + * + * ITR1_RMP can be one of the following values + * @arg @ref LL_TIM_TIM9_ITR1_RMP_TIM3_TRGO (*) + * @arg @ref LL_TIM_TIM9_ITR1_RMP_LPTIM (*) + * + * TIM11: one of the following values + * + * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO + * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO1 (*) + * @arg @ref LL_TIM_TIM11_TI1_RMP_HSE_RTC + * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO2 + * @arg @ref LL_TIM_TIM11_TI1_RMP_SPDIFRX (*) + * + * (*) Value not defined in all devices. \n + * + * @retval None + */ +__STATIC_INLINE void LL_TIM_SetRemap(TIM_TypeDef *TIMx, uint32_t Remap) +{ +#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) + if ((Remap & LL_TIM_LPTIM_REMAP_MASK) == LL_TIM_LPTIM_REMAP_MASK) + { + /* Connect TIMx internal trigger to LPTIM1 output */ + SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN); + MODIFY_REG(LPTIM1->OR, + (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), + Remap & ~(LL_TIM_LPTIM_REMAP_MASK)); + } + else + { + MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); + } +#else + MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); +#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_FLAG_Management FLAG-Management + * @{ + */ +/** + * @brief Clear the update interrupt flag (UIF). + * @rmtoll SR UIF LL_TIM_ClearFlag_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_UPDATE(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_UIF)); +} + +/** + * @brief Indicate whether update interrupt flag (UIF) is set (update interrupt is pending). + * @rmtoll SR UIF LL_TIM_IsActiveFlag_UPDATE + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_UPDATE(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_UIF) == (TIM_SR_UIF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 1 interrupt flag (CC1F). + * @rmtoll SR CC1IF LL_TIM_ClearFlag_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC1(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC1IF)); +} + +/** + * @brief Indicate whether Capture/Compare 1 interrupt flag (CC1F) is set (Capture/Compare 1 interrupt is pending). + * @rmtoll SR CC1IF LL_TIM_IsActiveFlag_CC1 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC1IF) == (TIM_SR_CC1IF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 2 interrupt flag (CC2F). + * @rmtoll SR CC2IF LL_TIM_ClearFlag_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC2(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC2IF)); +} + +/** + * @brief Indicate whether Capture/Compare 2 interrupt flag (CC2F) is set (Capture/Compare 2 interrupt is pending). + * @rmtoll SR CC2IF LL_TIM_IsActiveFlag_CC2 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC2IF) == (TIM_SR_CC2IF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 3 interrupt flag (CC3F). + * @rmtoll SR CC3IF LL_TIM_ClearFlag_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC3(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC3IF)); +} + +/** + * @brief Indicate whether Capture/Compare 3 interrupt flag (CC3F) is set (Capture/Compare 3 interrupt is pending). + * @rmtoll SR CC3IF LL_TIM_IsActiveFlag_CC3 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC3IF) == (TIM_SR_CC3IF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 4 interrupt flag (CC4F). + * @rmtoll SR CC4IF LL_TIM_ClearFlag_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC4(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC4IF)); +} + +/** + * @brief Indicate whether Capture/Compare 4 interrupt flag (CC4F) is set (Capture/Compare 4 interrupt is pending). + * @rmtoll SR CC4IF LL_TIM_IsActiveFlag_CC4 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC4IF) == (TIM_SR_CC4IF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the commutation interrupt flag (COMIF). + * @rmtoll SR COMIF LL_TIM_ClearFlag_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_COM(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_COMIF)); +} + +/** + * @brief Indicate whether commutation interrupt flag (COMIF) is set (commutation interrupt is pending). + * @rmtoll SR COMIF LL_TIM_IsActiveFlag_COM + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_COM(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_COMIF) == (TIM_SR_COMIF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the trigger interrupt flag (TIF). + * @rmtoll SR TIF LL_TIM_ClearFlag_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_TRIG(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_TIF)); +} + +/** + * @brief Indicate whether trigger interrupt flag (TIF) is set (trigger interrupt is pending). + * @rmtoll SR TIF LL_TIM_IsActiveFlag_TRIG + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_TRIG(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_TIF) == (TIM_SR_TIF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the break interrupt flag (BIF). + * @rmtoll SR BIF LL_TIM_ClearFlag_BRK + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_BRK(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_BIF)); +} + +/** + * @brief Indicate whether break interrupt flag (BIF) is set (break interrupt is pending). + * @rmtoll SR BIF LL_TIM_IsActiveFlag_BRK + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_BRK(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_BIF) == (TIM_SR_BIF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 1 over-capture interrupt flag (CC1OF). + * @rmtoll SR CC1OF LL_TIM_ClearFlag_CC1OVR + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC1OVR(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC1OF)); +} + +/** + * @brief Indicate whether Capture/Compare 1 over-capture interrupt flag (CC1OF) is set + * (Capture/Compare 1 interrupt is pending). + * @rmtoll SR CC1OF LL_TIM_IsActiveFlag_CC1OVR + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1OVR(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC1OF) == (TIM_SR_CC1OF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 2 over-capture interrupt flag (CC2OF). + * @rmtoll SR CC2OF LL_TIM_ClearFlag_CC2OVR + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC2OVR(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC2OF)); +} + +/** + * @brief Indicate whether Capture/Compare 2 over-capture interrupt flag (CC2OF) is set + * (Capture/Compare 2 over-capture interrupt is pending). + * @rmtoll SR CC2OF LL_TIM_IsActiveFlag_CC2OVR + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2OVR(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC2OF) == (TIM_SR_CC2OF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 3 over-capture interrupt flag (CC3OF). + * @rmtoll SR CC3OF LL_TIM_ClearFlag_CC3OVR + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC3OVR(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC3OF)); +} + +/** + * @brief Indicate whether Capture/Compare 3 over-capture interrupt flag (CC3OF) is set + * (Capture/Compare 3 over-capture interrupt is pending). + * @rmtoll SR CC3OF LL_TIM_IsActiveFlag_CC3OVR + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3OVR(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC3OF) == (TIM_SR_CC3OF)) ? 1UL : 0UL); +} + +/** + * @brief Clear the Capture/Compare 4 over-capture interrupt flag (CC4OF). + * @rmtoll SR CC4OF LL_TIM_ClearFlag_CC4OVR + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_ClearFlag_CC4OVR(TIM_TypeDef *TIMx) +{ + WRITE_REG(TIMx->SR, ~(TIM_SR_CC4OF)); +} + +/** + * @brief Indicate whether Capture/Compare 4 over-capture interrupt flag (CC4OF) is set + * (Capture/Compare 4 over-capture interrupt is pending). + * @rmtoll SR CC4OF LL_TIM_IsActiveFlag_CC4OVR + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4OVR(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->SR, TIM_SR_CC4OF) == (TIM_SR_CC4OF)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_IT_Management IT-Management + * @{ + */ +/** + * @brief Enable update interrupt (UIE). + * @rmtoll DIER UIE LL_TIM_EnableIT_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_UPDATE(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_UIE); +} + +/** + * @brief Disable update interrupt (UIE). + * @rmtoll DIER UIE LL_TIM_DisableIT_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_UPDATE(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_UIE); +} + +/** + * @brief Indicates whether the update interrupt (UIE) is enabled. + * @rmtoll DIER UIE LL_TIM_IsEnabledIT_UPDATE + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_UPDATE(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_UIE) == (TIM_DIER_UIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 1 interrupt (CC1IE). + * @rmtoll DIER CC1IE LL_TIM_EnableIT_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_CC1(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC1IE); +} + +/** + * @brief Disable capture/compare 1 interrupt (CC1IE). + * @rmtoll DIER CC1IE LL_TIM_DisableIT_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_CC1(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1IE); +} + +/** + * @brief Indicates whether the capture/compare 1 interrupt (CC1IE) is enabled. + * @rmtoll DIER CC1IE LL_TIM_IsEnabledIT_CC1 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC1(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1IE) == (TIM_DIER_CC1IE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 2 interrupt (CC2IE). + * @rmtoll DIER CC2IE LL_TIM_EnableIT_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_CC2(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC2IE); +} + +/** + * @brief Disable capture/compare 2 interrupt (CC2IE). + * @rmtoll DIER CC2IE LL_TIM_DisableIT_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_CC2(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2IE); +} + +/** + * @brief Indicates whether the capture/compare 2 interrupt (CC2IE) is enabled. + * @rmtoll DIER CC2IE LL_TIM_IsEnabledIT_CC2 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC2(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2IE) == (TIM_DIER_CC2IE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 3 interrupt (CC3IE). + * @rmtoll DIER CC3IE LL_TIM_EnableIT_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_CC3(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC3IE); +} + +/** + * @brief Disable capture/compare 3 interrupt (CC3IE). + * @rmtoll DIER CC3IE LL_TIM_DisableIT_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_CC3(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3IE); +} + +/** + * @brief Indicates whether the capture/compare 3 interrupt (CC3IE) is enabled. + * @rmtoll DIER CC3IE LL_TIM_IsEnabledIT_CC3 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC3(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3IE) == (TIM_DIER_CC3IE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 4 interrupt (CC4IE). + * @rmtoll DIER CC4IE LL_TIM_EnableIT_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_CC4(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC4IE); +} + +/** + * @brief Disable capture/compare 4 interrupt (CC4IE). + * @rmtoll DIER CC4IE LL_TIM_DisableIT_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_CC4(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4IE); +} + +/** + * @brief Indicates whether the capture/compare 4 interrupt (CC4IE) is enabled. + * @rmtoll DIER CC4IE LL_TIM_IsEnabledIT_CC4 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC4(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4IE) == (TIM_DIER_CC4IE)) ? 1UL : 0UL); +} + +/** + * @brief Enable commutation interrupt (COMIE). + * @rmtoll DIER COMIE LL_TIM_EnableIT_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_COM(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_COMIE); +} + +/** + * @brief Disable commutation interrupt (COMIE). + * @rmtoll DIER COMIE LL_TIM_DisableIT_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_COM(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_COMIE); +} + +/** + * @brief Indicates whether the commutation interrupt (COMIE) is enabled. + * @rmtoll DIER COMIE LL_TIM_IsEnabledIT_COM + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_COM(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_COMIE) == (TIM_DIER_COMIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable trigger interrupt (TIE). + * @rmtoll DIER TIE LL_TIM_EnableIT_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_TRIG(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_TIE); +} + +/** + * @brief Disable trigger interrupt (TIE). + * @rmtoll DIER TIE LL_TIM_DisableIT_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_TRIG(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_TIE); +} + +/** + * @brief Indicates whether the trigger interrupt (TIE) is enabled. + * @rmtoll DIER TIE LL_TIM_IsEnabledIT_TRIG + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_TRIG(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_TIE) == (TIM_DIER_TIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable break interrupt (BIE). + * @rmtoll DIER BIE LL_TIM_EnableIT_BRK + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableIT_BRK(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_BIE); +} + +/** + * @brief Disable break interrupt (BIE). + * @rmtoll DIER BIE LL_TIM_DisableIT_BRK + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableIT_BRK(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_BIE); +} + +/** + * @brief Indicates whether the break interrupt (BIE) is enabled. + * @rmtoll DIER BIE LL_TIM_IsEnabledIT_BRK + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_BRK(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_BIE) == (TIM_DIER_BIE)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_DMA_Management DMA Management + * @{ + */ +/** + * @brief Enable update DMA request (UDE). + * @rmtoll DIER UDE LL_TIM_EnableDMAReq_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_UPDATE(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_UDE); +} + +/** + * @brief Disable update DMA request (UDE). + * @rmtoll DIER UDE LL_TIM_DisableDMAReq_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_UPDATE(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_UDE); +} + +/** + * @brief Indicates whether the update DMA request (UDE) is enabled. + * @rmtoll DIER UDE LL_TIM_IsEnabledDMAReq_UPDATE + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_UPDATE(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_UDE) == (TIM_DIER_UDE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 1 DMA request (CC1DE). + * @rmtoll DIER CC1DE LL_TIM_EnableDMAReq_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_CC1(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC1DE); +} + +/** + * @brief Disable capture/compare 1 DMA request (CC1DE). + * @rmtoll DIER CC1DE LL_TIM_DisableDMAReq_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_CC1(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1DE); +} + +/** + * @brief Indicates whether the capture/compare 1 DMA request (CC1DE) is enabled. + * @rmtoll DIER CC1DE LL_TIM_IsEnabledDMAReq_CC1 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC1(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1DE) == (TIM_DIER_CC1DE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 2 DMA request (CC2DE). + * @rmtoll DIER CC2DE LL_TIM_EnableDMAReq_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_CC2(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC2DE); +} + +/** + * @brief Disable capture/compare 2 DMA request (CC2DE). + * @rmtoll DIER CC2DE LL_TIM_DisableDMAReq_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_CC2(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2DE); +} + +/** + * @brief Indicates whether the capture/compare 2 DMA request (CC2DE) is enabled. + * @rmtoll DIER CC2DE LL_TIM_IsEnabledDMAReq_CC2 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC2(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2DE) == (TIM_DIER_CC2DE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 3 DMA request (CC3DE). + * @rmtoll DIER CC3DE LL_TIM_EnableDMAReq_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_CC3(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC3DE); +} + +/** + * @brief Disable capture/compare 3 DMA request (CC3DE). + * @rmtoll DIER CC3DE LL_TIM_DisableDMAReq_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_CC3(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3DE); +} + +/** + * @brief Indicates whether the capture/compare 3 DMA request (CC3DE) is enabled. + * @rmtoll DIER CC3DE LL_TIM_IsEnabledDMAReq_CC3 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC3(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3DE) == (TIM_DIER_CC3DE)) ? 1UL : 0UL); +} + +/** + * @brief Enable capture/compare 4 DMA request (CC4DE). + * @rmtoll DIER CC4DE LL_TIM_EnableDMAReq_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_CC4(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_CC4DE); +} + +/** + * @brief Disable capture/compare 4 DMA request (CC4DE). + * @rmtoll DIER CC4DE LL_TIM_DisableDMAReq_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_CC4(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4DE); +} + +/** + * @brief Indicates whether the capture/compare 4 DMA request (CC4DE) is enabled. + * @rmtoll DIER CC4DE LL_TIM_IsEnabledDMAReq_CC4 + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC4(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4DE) == (TIM_DIER_CC4DE)) ? 1UL : 0UL); +} + +/** + * @brief Enable commutation DMA request (COMDE). + * @rmtoll DIER COMDE LL_TIM_EnableDMAReq_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_COM(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_COMDE); +} + +/** + * @brief Disable commutation DMA request (COMDE). + * @rmtoll DIER COMDE LL_TIM_DisableDMAReq_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_COM(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_COMDE); +} + +/** + * @brief Indicates whether the commutation DMA request (COMDE) is enabled. + * @rmtoll DIER COMDE LL_TIM_IsEnabledDMAReq_COM + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_COM(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_COMDE) == (TIM_DIER_COMDE)) ? 1UL : 0UL); +} + +/** + * @brief Enable trigger interrupt (TDE). + * @rmtoll DIER TDE LL_TIM_EnableDMAReq_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_EnableDMAReq_TRIG(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->DIER, TIM_DIER_TDE); +} + +/** + * @brief Disable trigger interrupt (TDE). + * @rmtoll DIER TDE LL_TIM_DisableDMAReq_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_DisableDMAReq_TRIG(TIM_TypeDef *TIMx) +{ + CLEAR_BIT(TIMx->DIER, TIM_DIER_TDE); +} + +/** + * @brief Indicates whether the trigger interrupt (TDE) is enabled. + * @rmtoll DIER TDE LL_TIM_IsEnabledDMAReq_TRIG + * @param TIMx Timer instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_TRIG(TIM_TypeDef *TIMx) +{ + return ((READ_BIT(TIMx->DIER, TIM_DIER_TDE) == (TIM_DIER_TDE)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup TIM_LL_EF_EVENT_Management EVENT-Management + * @{ + */ +/** + * @brief Generate an update event. + * @rmtoll EGR UG LL_TIM_GenerateEvent_UPDATE + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_UPDATE(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_UG); +} + +/** + * @brief Generate Capture/Compare 1 event. + * @rmtoll EGR CC1G LL_TIM_GenerateEvent_CC1 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_CC1(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_CC1G); +} + +/** + * @brief Generate Capture/Compare 2 event. + * @rmtoll EGR CC2G LL_TIM_GenerateEvent_CC2 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_CC2(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_CC2G); +} + +/** + * @brief Generate Capture/Compare 3 event. + * @rmtoll EGR CC3G LL_TIM_GenerateEvent_CC3 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_CC3(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_CC3G); +} + +/** + * @brief Generate Capture/Compare 4 event. + * @rmtoll EGR CC4G LL_TIM_GenerateEvent_CC4 + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_CC4(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_CC4G); +} + +/** + * @brief Generate commutation event. + * @rmtoll EGR COMG LL_TIM_GenerateEvent_COM + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_COM(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_COMG); +} + +/** + * @brief Generate trigger event. + * @rmtoll EGR TG LL_TIM_GenerateEvent_TRIG + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_TRIG(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_TG); +} + +/** + * @brief Generate break event. + * @rmtoll EGR BG LL_TIM_GenerateEvent_BRK + * @param TIMx Timer instance + * @retval None + */ +__STATIC_INLINE void LL_TIM_GenerateEvent_BRK(TIM_TypeDef *TIMx) +{ + SET_BIT(TIMx->EGR, TIM_EGR_BG); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup TIM_LL_EF_Init Initialisation and deinitialisation functions + * @{ + */ + +ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx); +void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct); +ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct); +void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); +ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); +void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); +ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct); +void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); +ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); +void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); +ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); +void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); +ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_TIM_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h index e07c232..64f59b0 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h @@ -1,2521 +1,2521 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usart.h - * @author MCD Application Team - * @brief Header file of USART LL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_USART_H -#define __STM32F4xx_LL_USART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) - -/** @defgroup USART_LL USART - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup USART_LL_Private_Constants USART Private Constants - * @{ - */ - -/* Defines used for the bit position in the register and perform offsets*/ -#define USART_POSITION_GTPR_GT USART_GTPR_GT_Pos -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_Private_Macros USART Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_ES_INIT USART Exported Init structures - * @{ - */ - -/** - * @brief LL USART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/ - - uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_LL_EC_DATAWIDTH. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_LL_EC_STOPBITS. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_LL_EC_PARITY. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/ - - uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_DIRECTION. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/ - - uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_HWCONTROL. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/ - - uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8. - This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/ - -} LL_USART_InitTypeDef; - -/** - * @brief LL USART Clock Init Structure definition - */ -typedef struct -{ - uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_CLOCK. - - USART HW configuration can be modified afterwards using unitary functions - @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput(). - For more details, refer to description of this function. */ - - uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref USART_LL_EC_POLARITY. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity(). - For more details, refer to description of this function. */ - - uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_LL_EC_PHASE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase(). - For more details, refer to description of this function. */ - - uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput(). - For more details, refer to description of this function. */ - -} LL_USART_ClockInitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Constants USART Exported Constants - * @{ - */ - -/** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_USART_ReadReg function - * @{ - */ -#define LL_USART_SR_PE USART_SR_PE /*!< Parity error flag */ -#define LL_USART_SR_FE USART_SR_FE /*!< Framing error flag */ -#define LL_USART_SR_NE USART_SR_NE /*!< Noise detected flag */ -#define LL_USART_SR_ORE USART_SR_ORE /*!< Overrun error flag */ -#define LL_USART_SR_IDLE USART_SR_IDLE /*!< Idle line detected flag */ -#define LL_USART_SR_RXNE USART_SR_RXNE /*!< Read data register not empty flag */ -#define LL_USART_SR_TC USART_SR_TC /*!< Transmission complete flag */ -#define LL_USART_SR_TXE USART_SR_TXE /*!< Transmit data register empty flag */ -#define LL_USART_SR_LBD USART_SR_LBD /*!< LIN break detection flag */ -#define LL_USART_SR_CTS USART_SR_CTS /*!< CTS flag */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions - * @{ - */ -#define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */ -#define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */ -#define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */ -#define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */ -#define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */ -#define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */ -#define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */ -#define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DIRECTION Communication Direction - * @{ - */ -#define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */ -#define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */ -#define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */ -#define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PARITY Parity Control - * @{ - */ -#define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */ -#define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */ -#define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_WAKEUP Wakeup - * @{ - */ -#define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */ -#define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DATAWIDTH Datawidth - * @{ - */ -#define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */ -#define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_OVERSAMPLING Oversampling - * @{ - */ -#define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */ -#define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EC_CLOCK Clock Signal - * @{ - */ - -#define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */ -#define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse - * @{ - */ -#define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */ -#define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PHASE Clock Phase - * @{ - */ -#define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */ -#define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/ -#define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_STOPBITS Stop Bits - * @{ - */ -#define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */ -#define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */ -#define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */ -#define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_HWCONTROL Hardware Control - * @{ - */ -#define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */ -#define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */ -#define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */ -#define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IRDA_POWER IrDA Power - * @{ - */ -#define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */ -#define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length - * @{ - */ -#define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */ -#define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Macros USART Exported Macros - * @{ - */ - -/** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case - */ -#define __LL_USART_DIV_SAMPLING8_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(2*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 8)\ - + 50) / 100) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */ -#define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - ((__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0xF8) << 1)) + \ - (__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0x07)) - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case - */ -#define __LL_USART_DIV_SAMPLING16_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(4*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 16)\ - + 50) / 100) -/* USART BRR = mantissa + overflow + fraction - = (USART DIVMANT << 4) + (USART DIVFRAQ & 0xF0) + (USART DIVFRAQ & 0x0F) */ -#define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0xF0)) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0x0F)) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup USART_LL_Exported_Functions USART Exported Functions - * @{ - */ - -/** @defgroup USART_LL_EF_Configuration Configuration functions - * @{ - */ - -/** - * @brief USART Enable - * @rmtoll CR1 UE LL_USART_Enable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief USART Disable (all USART prescalers and outputs are disabled) - * @note When USART is disabled, USART prescalers and outputs are stopped immediately, - * and current operations are discarded. The configuration of the USART is kept, but all the status - * flags, in the USARTx_SR are set to their default values. - * @rmtoll CR1 UE LL_USART_Disable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief Indicate if USART is enabled - * @rmtoll CR1 UE LL_USART_IsEnabled - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE)); -} - -/** - * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit) - * @rmtoll CR1 RE LL_USART_EnableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Receiver Disable - * @rmtoll CR1 RE LL_USART_DisableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Transmitter Enable - * @rmtoll CR1 TE LL_USART_EnableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Transmitter Disable - * @rmtoll CR1 TE LL_USART_DisableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Configure simultaneously enabled/disabled states - * of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_SetTransferDirection\n - * CR1 TE LL_USART_SetTransferDirection - * @param USARTx USART Instance - * @param TransferDirection This parameter can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - * @retval None - */ -__STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection) -{ - ATOMIC_MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection); -} - -/** - * @brief Return enabled/disabled states of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_GetTransferDirection\n - * CR1 TE LL_USART_GetTransferDirection - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - */ -__STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE)); -} - -/** - * @brief Configure Parity (enabled/disabled and parity mode if enabled). - * @note This function selects if hardware parity control (generation and detection) is enabled or disabled. - * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position - * (9th or 8th bit depending on data width) and parity is checked on the received data. - * @rmtoll CR1 PS LL_USART_SetParity\n - * CR1 PCE LL_USART_SetParity - * @param USARTx USART Instance - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @retval None - */ -__STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity); -} - -/** - * @brief Return Parity configuration (enabled/disabled and parity mode if enabled) - * @rmtoll CR1 PS LL_USART_GetParity\n - * CR1 PCE LL_USART_GetParity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - */ -__STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE)); -} - -/** - * @brief Set Receiver Wake Up method from Mute mode. - * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod - * @param USARTx USART Instance - * @param Method This parameter can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - * @retval None - */ -__STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method); -} - -/** - * @brief Return Receiver Wake Up method from Mute mode - * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - */ -__STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE)); -} - -/** - * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_SetDataWidth - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth); -} - -/** - * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_GetDataWidth - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - */ -__STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M)); -} - -/** - * @brief Set Oversampling to 8-bit or 16-bit mode - * @rmtoll CR1 OVER8 LL_USART_SetOverSampling - * @param USARTx USART Instance - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling); -} - -/** - * @brief Return Oversampling mode - * @rmtoll CR1 OVER8 LL_USART_GetOverSampling - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - */ -__STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8)); -} - -/** - * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput - * @param USARTx USART Instance - * @param LastBitClockPulse This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse); -} - -/** - * @brief Retrieve Clock pulse of the last data bit output configuration - * (Last bit Clock pulse output to the SCLK pin or not) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - */ -__STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL)); -} - -/** - * @brief Select the phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_SetClockPhase - * @param USARTx USART Instance - * @param ClockPhase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase); -} - -/** - * @brief Return phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_GetClockPhase - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA)); -} - -/** - * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_SetClockPolarity - * @param USARTx USART Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity); -} - -/** - * @brief Return polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_GetClockPolarity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL)); -} - -/** - * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function - * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function - * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function - * @rmtoll CR2 CPHA LL_USART_ConfigClock\n - * CR2 CPOL LL_USART_ConfigClock\n - * CR2 LBCL LL_USART_ConfigClock - * @param USARTx USART Instance - * @param Phase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @param LBCPOutput This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput); -} - -/** - * @brief Enable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Disable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Indicate if Clock output on SCLK pin is enabled - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN)); -} - -/** - * @brief Set the length of the stop bits - * @rmtoll CR2 STOP LL_USART_SetStopBitsLength - * @param USARTx USART Instance - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Retrieve the length of the stop bits - * @rmtoll CR2 STOP LL_USART_GetStopBitsLength - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - */ -__STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP)); -} - -/** - * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits) - * @note Call of this function is equivalent to following function call sequence : - * - Data Width configuration using @ref LL_USART_SetDataWidth() function - * - Parity Control and mode configuration using @ref LL_USART_SetParity() function - * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function - * @rmtoll CR1 PS LL_USART_ConfigCharacter\n - * CR1 PCE LL_USART_ConfigCharacter\n - * CR1 M LL_USART_ConfigCharacter\n - * CR2 STOP LL_USART_ConfigCharacter - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity, - uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth); - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Set Address of the USART node. - * @note This is used in multiprocessor communication during Mute mode or Stop mode, - * for wake up with address mark detection. - * @rmtoll CR2 ADD LL_USART_SetNodeAddress - * @param USARTx USART Instance - * @param NodeAddress 4 bit Address of the USART node. - * @retval None - */ -__STATIC_INLINE void LL_USART_SetNodeAddress(USART_TypeDef *USARTx, uint32_t NodeAddress) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_ADD, (NodeAddress & USART_CR2_ADD)); -} - -/** - * @brief Return 4 bit Address of the USART node as set in ADD field of CR2. - * @note only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant) - * @rmtoll CR2 ADD LL_USART_GetNodeAddress - * @param USARTx USART Instance - * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255) - */ -__STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD)); -} - -/** - * @brief Enable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Disable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Enable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Disable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Configure HW Flow Control mode (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n - * CR3 CTSE LL_USART_SetHWFlowCtrl - * @param USARTx USART Instance - * @param HardwareFlowControl This parameter can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - * @retval None - */ -__STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl); -} - -/** - * @brief Return HW Flow Control configuration (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n - * CR3 CTSE LL_USART_GetHWFlowCtrl - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - */ -__STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE)); -} - -/** - * @brief Enable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Disable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Indicate if One bit sampling method is enabled - * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT)); -} - -/** - * @brief Configure USART BRR register for achieving expected Baud Rate value. - * @note Compute and set USARTDIV value in BRR Register (full BRR content) - * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values - * @note Peripheral clock and Baud rate values provided as function parameters should be valid - * (Baud rate value != 0) - * @rmtoll BRR BRR LL_USART_SetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @param BaudRate Baud Rate - * @retval None - */ -__STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling, - uint32_t BaudRate) -{ - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate)); - } - else - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate)); - } -} - -/** - * @brief Return current Baud Rate value, according to USARTDIV present in BRR register - * (full BRR content), and to used Peripheral Clock and Oversampling mode values - * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned. - * @rmtoll BRR BRR LL_USART_GetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval Baud Rate - */ -__STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling) -{ - uint32_t usartdiv = 0x0U; - uint32_t brrresult = 0x0U; - - usartdiv = USARTx->BRR; - - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - if ((usartdiv & 0xFFF7U) != 0U) - { - usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ; - brrresult = (PeriphClk * 2U) / usartdiv; - } - } - else - { - if ((usartdiv & 0xFFFFU) != 0U) - { - brrresult = PeriphClk / usartdiv; - } - } - return (brrresult); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature - * @{ - */ - -/** - * @brief Enable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_EnableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Disable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_DisableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Indicate if IrDA mode is enabled - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_IsEnabledIrda - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN)); -} - -/** - * @brief Configure IrDA Power Mode (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode - * @param USARTx USART Instance - * @param PowerMode This parameter can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_IRDA_POWER_LOW - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode); -} - -/** - * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP)); -} - -/** - * @brief Set Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler - * @param USARTx USART Instance - * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature - * @{ - */ - -/** - * @brief Enable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Disable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Indicate if Smartcard NACK transmission is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK)); -} - -/** - * @brief Enable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_EnableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Disable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_DisableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Indicate if Smartcard mode is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN)); -} - -/** - * @brief Set Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0 and Max_Data=31 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler - * @param USARTx USART Instance - * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime - * @param USARTx USART Instance - * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_POSITION_GTPR_GT); -} - -/** - * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime - * @param USARTx USART Instance - * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_POSITION_GTPR_GT); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature - * @{ - */ - -/** - * @brief Enable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Disable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Indicate if Single Wire Half-Duplex mode is enabled - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature - * @{ - */ - -/** - * @brief Set LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen - * @param USARTx USART Instance - * @param LINBDLength This parameter can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength); -} - -/** - * @brief Return LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - */ -__STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL)); -} - -/** - * @brief Enable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_EnableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Disable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_DisableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Indicate if LIN mode is enabled - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services - * @{ - */ - -/** - * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART) - * @note In UART mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Asynchronous Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n - * CR2 CLKEN LL_USART_ConfigAsyncMode\n - * CR3 SCEN LL_USART_ConfigAsyncMode\n - * CR3 IREN LL_USART_ConfigAsyncMode\n - * CR3 HDSEL LL_USART_ConfigAsyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx) -{ - /* In Asynchronous mode, the following bits must be kept cleared: - - LINEN, CLKEN bits in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Synchronous Mode - * @note In Synchronous mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the USART in Synchronous mode. - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * @note Other remaining configurations items related to Synchronous Mode - * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n - * CR2 CLKEN LL_USART_ConfigSyncMode\n - * CR3 SCEN LL_USART_ConfigSyncMode\n - * CR3 IREN LL_USART_ConfigSyncMode\n - * CR3 HDSEL LL_USART_ConfigSyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx) -{ - /* In Synchronous mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); - /* set the UART/USART in Synchronous mode */ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in LIN Mode - * @note In LIN mode, the following bits must be kept cleared: - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also set the UART/USART in LIN mode. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function - * @note Other remaining configurations items related to LIN Mode - * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using - * dedicated functions - * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n - * CR2 STOP LL_USART_ConfigLINMode\n - * CR2 LINEN LL_USART_ConfigLINMode\n - * CR3 IREN LL_USART_ConfigLINMode\n - * CR3 SCEN LL_USART_ConfigLINMode\n - * CR3 HDSEL LL_USART_ConfigLINMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx) -{ - /* In LIN mode, the following bits must be kept cleared: - - STOP and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL)); - /* Set the UART/USART in LIN mode */ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode - * @note In Half Duplex mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * This function also sets the UART/USART in Half Duplex mode. - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function - * @note Other remaining configurations items related to Half Duplex Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n - * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n - * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n - * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n - * CR3 IREN LL_USART_ConfigHalfDuplexMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx) -{ - /* In Half Duplex mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN)); - /* set the UART/USART in Half Duplex mode */ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Smartcard Mode - * @note In Smartcard mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also configures Stop bits to 1.5 bits and - * sets the USART in Smartcard mode (SCEN bit). - * Clock Output is also enabled (CLKEN). - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function - * @note Other remaining configurations items related to Smartcard Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n - * CR2 STOP LL_USART_ConfigSmartcardMode\n - * CR2 CLKEN LL_USART_ConfigSmartcardMode\n - * CR3 HDSEL LL_USART_ConfigSmartcardMode\n - * CR3 SCEN LL_USART_ConfigSmartcardMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx) -{ - /* In Smartcard mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); - /* Configure Stop bits to 1.5 bits */ - /* Synchronous mode is activated by default */ - SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN)); - /* set the UART/USART in Smartcard mode */ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Irda Mode - * @note In IRDA mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the UART/USART in IRDA mode (IREN bit). - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function - * @note Other remaining configurations items related to Irda Mode - * (as Baud Rate, Word length, Power mode, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n - * CR2 CLKEN LL_USART_ConfigIrdaMode\n - * CR2 STOP LL_USART_ConfigIrdaMode\n - * CR3 SCEN LL_USART_ConfigIrdaMode\n - * CR3 HDSEL LL_USART_ConfigIrdaMode\n - * CR3 IREN LL_USART_ConfigIrdaMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx) -{ - /* In IRDA mode, the following bits must be kept cleared: - - LINEN, STOP and CLKEN bits in the USART_CR2 register, - - SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); - /* set the UART/USART in IRDA mode */ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Multi processor Mode - * (several USARTs connected in a network, one of the USARTs can be the master, - * its TX output connected to the RX inputs of the other slaves USARTs). - * @note In MultiProcessor mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Multi processor Mode - * (as Baud Rate, Wake Up Method, Node address, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n - * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n - * CR3 SCEN LL_USART_ConfigMultiProcessMode\n - * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n - * CR3 IREN LL_USART_ConfigMultiProcessMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx) -{ - /* In Multi Processor mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Check if the USART Parity Error Flag is set or not - * @rmtoll SR PE LL_USART_IsActiveFlag_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_PE) == (USART_SR_PE)); -} - -/** - * @brief Check if the USART Framing Error Flag is set or not - * @rmtoll SR FE LL_USART_IsActiveFlag_FE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_FE) == (USART_SR_FE)); -} - -/** - * @brief Check if the USART Noise error detected Flag is set or not - * @rmtoll SR NF LL_USART_IsActiveFlag_NE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_NE) == (USART_SR_NE)); -} - -/** - * @brief Check if the USART OverRun Error Flag is set or not - * @rmtoll SR ORE LL_USART_IsActiveFlag_ORE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_ORE) == (USART_SR_ORE)); -} - -/** - * @brief Check if the USART IDLE line detected Flag is set or not - * @rmtoll SR IDLE LL_USART_IsActiveFlag_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_IDLE) == (USART_SR_IDLE)); -} - -/** - * @brief Check if the USART Read Data Register Not Empty Flag is set or not - * @rmtoll SR RXNE LL_USART_IsActiveFlag_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_RXNE) == (USART_SR_RXNE)); -} - -/** - * @brief Check if the USART Transmission Complete Flag is set or not - * @rmtoll SR TC LL_USART_IsActiveFlag_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TC) == (USART_SR_TC)); -} - -/** - * @brief Check if the USART Transmit Data Register Empty Flag is set or not - * @rmtoll SR TXE LL_USART_IsActiveFlag_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TXE) == (USART_SR_TXE)); -} - -/** - * @brief Check if the USART LIN Break Detection Flag is set or not - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_IsActiveFlag_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_LBD) == (USART_SR_LBD)); -} - -/** - * @brief Check if the USART CTS Flag is set or not - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_IsActiveFlag_nCTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_CTS) == (USART_SR_CTS)); -} - -/** - * @brief Check if the USART Send Break Flag is set or not - * @rmtoll CR1 SBK LL_USART_IsActiveFlag_SBK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_SBK) == (USART_CR1_SBK)); -} - -/** - * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not - * @rmtoll CR1 RWU LL_USART_IsActiveFlag_RWU - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RWU) == (USART_CR1_RWU)); -} - -/** - * @brief Clear Parity Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * NE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR PE LL_USART_ClearFlag_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Framing Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, ORE, IDLE would also be cleared. - * @rmtoll SR FE LL_USART_ClearFlag_FE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Noise detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR NF LL_USART_ClearFlag_NE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear OverRun Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, IDLE would also be cleared. - * @rmtoll SR ORE LL_USART_ClearFlag_ORE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear IDLE line detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, ORE would also be cleared. - * @rmtoll SR IDLE LL_USART_ClearFlag_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Transmission Complete Flag - * @rmtoll SR TC LL_USART_ClearFlag_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_TC)); -} - -/** - * @brief Clear RX Not Empty Flag - * @rmtoll SR RXNE LL_USART_ClearFlag_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_RXNE(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_RXNE)); -} - -/** - * @brief Clear LIN Break Detection Flag - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_ClearFlag_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_LBD)); -} - -/** - * @brief Clear CTS Interrupt Flag - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_ClearFlag_nCTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_CTS)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Enable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Enable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_EnableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Enable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Enable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_EnableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Enable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Enable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Enable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Disable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Disable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Disable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_DisableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Disable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Disable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_DisableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Disable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Disable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Disable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Check if the USART IDLE Interrupt source is enabled or disabled. - * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE)); -} - -/** - * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled. - * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE)); -} - -/** - * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled. - * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE)); -} - -/** - * @brief Check if the USART TX Empty Interrupt is enabled or disabled. - * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE)); -} - -/** - * @brief Check if the USART Parity Error Interrupt is enabled or disabled. - * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE)); -} - -/** - * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE)); -} - -/** - * @brief Check if the USART Error Interrupt is enabled or disabled. - * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE)); -} - -/** - * @brief Check if the USART CTS Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_DMA_Management DMA_Management - * @{ - */ - -/** - * @brief Enable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Disable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Check if DMA Mode is enabled for reception - * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR)); -} - -/** - * @brief Enable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Disable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Check if DMA Mode is enabled for transmission - * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT)); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll DR DR LL_USART_DMA_GetRegAddr - * @note Address of Data Register is valid for both Transmit and Receive transfers. - * @param USARTx USART Instance - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx) -{ - /* return address of DR register */ - return ((uint32_t) &(USARTx->DR)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Read Receiver Data register (Receive Data value, 8 bits) - * @rmtoll DR DR LL_USART_ReceiveData8 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx) -{ - return (uint8_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Read Receiver Data register (Receive Data value, 9 bits) - * @rmtoll DR DR LL_USART_ReceiveData9 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x1FF - */ -__STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx) -{ - return (uint16_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits) - * @rmtoll DR DR LL_USART_TransmitData8 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value) -{ - USARTx->DR = Value; -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits) - * @rmtoll DR DR LL_USART_TransmitData9 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0x1FF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value) -{ - USARTx->DR = Value & 0x1FFU; -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Execution Execution - * @{ - */ - -/** - * @brief Request Break sending - * @rmtoll CR1 SBK LL_USART_RequestBreakSending - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_SBK); -} - -/** - * @brief Put USART in Mute mode - * @rmtoll CR1 RWU LL_USART_RequestEnterMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @brief Put USART in Active mode - * @rmtoll CR1 RWU LL_USART_RequestExitMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestExitMuteMode(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EF_Init Initialization and de-initialization functions - * @{ - */ -ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx); -ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct); -void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct); -ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_USART_H */ - +/** + ****************************************************************************** + * @file stm32f4xx_ll_usart.h + * @author MCD Application Team + * @brief Header file of USART LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_USART_H +#define __STM32F4xx_LL_USART_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) + +/** @defgroup USART_LL USART + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup USART_LL_Private_Constants USART Private Constants + * @{ + */ + +/* Defines used for the bit position in the register and perform offsets*/ +#define USART_POSITION_GTPR_GT USART_GTPR_GT_Pos +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup USART_LL_Private_Macros USART Private Macros + * @{ + */ +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup USART_LL_ES_INIT USART Exported Init structures + * @{ + */ + +/** + * @brief LL USART Init Structure definition + */ +typedef struct +{ + uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/ + + uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_LL_EC_DATAWIDTH. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/ + + uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_LL_EC_STOPBITS. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/ + + uint32_t Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_LL_EC_PARITY. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/ + + uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_LL_EC_DIRECTION. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/ + + uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. + This parameter can be a value of @ref USART_LL_EC_HWCONTROL. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/ + + uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8. + This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING. + + This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/ + +} LL_USART_InitTypeDef; + +/** + * @brief LL USART Clock Init Structure definition + */ +typedef struct +{ + uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_LL_EC_CLOCK. + + USART HW configuration can be modified afterwards using unitary functions + @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput(). + For more details, refer to description of this function. */ + + uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock. + This parameter can be a value of @ref USART_LL_EC_POLARITY. + + USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity(). + For more details, refer to description of this function. */ + + uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_LL_EC_PHASE. + + USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase(). + For more details, refer to description of this function. */ + + uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE. + + USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput(). + For more details, refer to description of this function. */ + +} LL_USART_ClockInitTypeDef; + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup USART_LL_Exported_Constants USART Exported Constants + * @{ + */ + +/** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_USART_ReadReg function + * @{ + */ +#define LL_USART_SR_PE USART_SR_PE /*!< Parity error flag */ +#define LL_USART_SR_FE USART_SR_FE /*!< Framing error flag */ +#define LL_USART_SR_NE USART_SR_NE /*!< Noise detected flag */ +#define LL_USART_SR_ORE USART_SR_ORE /*!< Overrun error flag */ +#define LL_USART_SR_IDLE USART_SR_IDLE /*!< Idle line detected flag */ +#define LL_USART_SR_RXNE USART_SR_RXNE /*!< Read data register not empty flag */ +#define LL_USART_SR_TC USART_SR_TC /*!< Transmission complete flag */ +#define LL_USART_SR_TXE USART_SR_TXE /*!< Transmit data register empty flag */ +#define LL_USART_SR_LBD USART_SR_LBD /*!< LIN break detection flag */ +#define LL_USART_SR_CTS USART_SR_CTS /*!< CTS flag */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions + * @{ + */ +#define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */ +#define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */ +#define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */ +#define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */ +#define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */ +#define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */ +#define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */ +#define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_DIRECTION Communication Direction + * @{ + */ +#define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */ +#define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */ +#define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */ +#define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_PARITY Parity Control + * @{ + */ +#define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */ +#define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */ +#define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_WAKEUP Wakeup + * @{ + */ +#define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */ +#define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_DATAWIDTH Datawidth + * @{ + */ +#define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */ +#define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_OVERSAMPLING Oversampling + * @{ + */ +#define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */ +#define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */ +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup USART_LL_EC_CLOCK Clock Signal + * @{ + */ + +#define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */ +#define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */ +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse + * @{ + */ +#define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */ +#define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_PHASE Clock Phase + * @{ + */ +#define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */ +#define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_POLARITY Clock Polarity + * @{ + */ +#define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/ +#define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_STOPBITS Stop Bits + * @{ + */ +#define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */ +#define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */ +#define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */ +#define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_HWCONTROL Hardware Control + * @{ + */ +#define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */ +#define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */ +#define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */ +#define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_IRDA_POWER IrDA Power + * @{ + */ +#define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */ +#define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */ +/** + * @} + */ + +/** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length + * @{ + */ +#define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */ +#define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup USART_LL_Exported_Macros USART Exported Macros + * @{ + */ + +/** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in USART register + * @param __INSTANCE__ USART Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in USART register + * @param __INSTANCE__ USART Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper + * @{ + */ + +/** + * @brief Compute USARTDIV value according to Peripheral Clock and + * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned) + * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance + * @param __BAUDRATE__ Baud rate value to achieve + * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case + */ +#define __LL_USART_DIV_SAMPLING8_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(2*((uint64_t)(__BAUDRATE__))))) +#define __LL_USART_DIVMANT_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__))/100) +#define __LL_USART_DIVFRAQ_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 8)\ + + 50) / 100) +/* UART BRR = mantissa + overflow + fraction + = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */ +#define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ + ((__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0xF8) << 1)) + \ + (__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0x07)) + +/** + * @brief Compute USARTDIV value according to Peripheral Clock and + * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned) + * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance + * @param __BAUDRATE__ Baud rate value to achieve + * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case + */ +#define __LL_USART_DIV_SAMPLING16_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(4*((uint64_t)(__BAUDRATE__))))) +#define __LL_USART_DIVMANT_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__))/100) +#define __LL_USART_DIVFRAQ_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 16)\ + + 50) / 100) +/* USART BRR = mantissa + overflow + fraction + = (USART DIVMANT << 4) + (USART DIVFRAQ & 0xF0) + (USART DIVFRAQ & 0x0F) */ +#define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ + (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0xF0)) + \ + (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0x0F)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup USART_LL_Exported_Functions USART Exported Functions + * @{ + */ + +/** @defgroup USART_LL_EF_Configuration Configuration functions + * @{ + */ + +/** + * @brief USART Enable + * @rmtoll CR1 UE LL_USART_Enable + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR1, USART_CR1_UE); +} + +/** + * @brief USART Disable (all USART prescalers and outputs are disabled) + * @note When USART is disabled, USART prescalers and outputs are stopped immediately, + * and current operations are discarded. The configuration of the USART is kept, but all the status + * flags, in the USARTx_SR are set to their default values. + * @rmtoll CR1 UE LL_USART_Disable + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR1, USART_CR1_UE); +} + +/** + * @brief Indicate if USART is enabled + * @rmtoll CR1 UE LL_USART_IsEnabled + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE)); +} + +/** + * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit) + * @rmtoll CR1 RE LL_USART_EnableDirectionRx + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RE); +} + +/** + * @brief Receiver Disable + * @rmtoll CR1 RE LL_USART_DisableDirectionRx + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RE); +} + +/** + * @brief Transmitter Enable + * @rmtoll CR1 TE LL_USART_EnableDirectionTx + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TE); +} + +/** + * @brief Transmitter Disable + * @rmtoll CR1 TE LL_USART_DisableDirectionTx + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TE); +} + +/** + * @brief Configure simultaneously enabled/disabled states + * of Transmitter and Receiver + * @rmtoll CR1 RE LL_USART_SetTransferDirection\n + * CR1 TE LL_USART_SetTransferDirection + * @param USARTx USART Instance + * @param TransferDirection This parameter can be one of the following values: + * @arg @ref LL_USART_DIRECTION_NONE + * @arg @ref LL_USART_DIRECTION_RX + * @arg @ref LL_USART_DIRECTION_TX + * @arg @ref LL_USART_DIRECTION_TX_RX + * @retval None + */ +__STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection) +{ + ATOMIC_MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection); +} + +/** + * @brief Return enabled/disabled states of Transmitter and Receiver + * @rmtoll CR1 RE LL_USART_GetTransferDirection\n + * CR1 TE LL_USART_GetTransferDirection + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_DIRECTION_NONE + * @arg @ref LL_USART_DIRECTION_RX + * @arg @ref LL_USART_DIRECTION_TX + * @arg @ref LL_USART_DIRECTION_TX_RX + */ +__STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE)); +} + +/** + * @brief Configure Parity (enabled/disabled and parity mode if enabled). + * @note This function selects if hardware parity control (generation and detection) is enabled or disabled. + * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position + * (9th or 8th bit depending on data width) and parity is checked on the received data. + * @rmtoll CR1 PS LL_USART_SetParity\n + * CR1 PCE LL_USART_SetParity + * @param USARTx USART Instance + * @param Parity This parameter can be one of the following values: + * @arg @ref LL_USART_PARITY_NONE + * @arg @ref LL_USART_PARITY_EVEN + * @arg @ref LL_USART_PARITY_ODD + * @retval None + */ +__STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity) +{ + MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity); +} + +/** + * @brief Return Parity configuration (enabled/disabled and parity mode if enabled) + * @rmtoll CR1 PS LL_USART_GetParity\n + * CR1 PCE LL_USART_GetParity + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_PARITY_NONE + * @arg @ref LL_USART_PARITY_EVEN + * @arg @ref LL_USART_PARITY_ODD + */ +__STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE)); +} + +/** + * @brief Set Receiver Wake Up method from Mute mode. + * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod + * @param USARTx USART Instance + * @param Method This parameter can be one of the following values: + * @arg @ref LL_USART_WAKEUP_IDLELINE + * @arg @ref LL_USART_WAKEUP_ADDRESSMARK + * @retval None + */ +__STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method) +{ + MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method); +} + +/** + * @brief Return Receiver Wake Up method from Mute mode + * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_WAKEUP_IDLELINE + * @arg @ref LL_USART_WAKEUP_ADDRESSMARK + */ +__STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE)); +} + +/** + * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits) + * @rmtoll CR1 M LL_USART_SetDataWidth + * @param USARTx USART Instance + * @param DataWidth This parameter can be one of the following values: + * @arg @ref LL_USART_DATAWIDTH_8B + * @arg @ref LL_USART_DATAWIDTH_9B + * @retval None + */ +__STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth) +{ + MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth); +} + +/** + * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits) + * @rmtoll CR1 M LL_USART_GetDataWidth + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_DATAWIDTH_8B + * @arg @ref LL_USART_DATAWIDTH_9B + */ +__STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M)); +} + +/** + * @brief Set Oversampling to 8-bit or 16-bit mode + * @rmtoll CR1 OVER8 LL_USART_SetOverSampling + * @param USARTx USART Instance + * @param OverSampling This parameter can be one of the following values: + * @arg @ref LL_USART_OVERSAMPLING_16 + * @arg @ref LL_USART_OVERSAMPLING_8 + * @retval None + */ +__STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling) +{ + MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling); +} + +/** + * @brief Return Oversampling mode + * @rmtoll CR1 OVER8 LL_USART_GetOverSampling + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_OVERSAMPLING_16 + * @arg @ref LL_USART_OVERSAMPLING_8 + */ +__STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8)); +} + +/** + * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput + * @param USARTx USART Instance + * @param LastBitClockPulse This parameter can be one of the following values: + * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT + * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT + * @retval None + */ +__STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse); +} + +/** + * @brief Retrieve Clock pulse of the last data bit output configuration + * (Last bit Clock pulse output to the SCLK pin or not) + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT + * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT + */ +__STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL)); +} + +/** + * @brief Select the phase of the clock output on the SCLK pin in synchronous mode + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CPHA LL_USART_SetClockPhase + * @param USARTx USART Instance + * @param ClockPhase This parameter can be one of the following values: + * @arg @ref LL_USART_PHASE_1EDGE + * @arg @ref LL_USART_PHASE_2EDGE + * @retval None + */ +__STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase); +} + +/** + * @brief Return phase of the clock output on the SCLK pin in synchronous mode + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CPHA LL_USART_GetClockPhase + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_PHASE_1EDGE + * @arg @ref LL_USART_PHASE_2EDGE + */ +__STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA)); +} + +/** + * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CPOL LL_USART_SetClockPolarity + * @param USARTx USART Instance + * @param ClockPolarity This parameter can be one of the following values: + * @arg @ref LL_USART_POLARITY_LOW + * @arg @ref LL_USART_POLARITY_HIGH + * @retval None + */ +__STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity); +} + +/** + * @brief Return polarity of the clock output on the SCLK pin in synchronous mode + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CPOL LL_USART_GetClockPolarity + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_POLARITY_LOW + * @arg @ref LL_USART_POLARITY_HIGH + */ +__STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL)); +} + +/** + * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse) + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function + * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function + * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function + * @rmtoll CR2 CPHA LL_USART_ConfigClock\n + * CR2 CPOL LL_USART_ConfigClock\n + * CR2 LBCL LL_USART_ConfigClock + * @param USARTx USART Instance + * @param Phase This parameter can be one of the following values: + * @arg @ref LL_USART_PHASE_1EDGE + * @arg @ref LL_USART_PHASE_2EDGE + * @param Polarity This parameter can be one of the following values: + * @arg @ref LL_USART_POLARITY_LOW + * @arg @ref LL_USART_POLARITY_HIGH + * @param LBCPOutput This parameter can be one of the following values: + * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT + * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput); +} + +/** + * @brief Enable Clock output on SCLK pin + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR2, USART_CR2_CLKEN); +} + +/** + * @brief Disable Clock output on SCLK pin + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN); +} + +/** + * @brief Indicate if Clock output on SCLK pin is enabled + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN)); +} + +/** + * @brief Set the length of the stop bits + * @rmtoll CR2 STOP LL_USART_SetStopBitsLength + * @param USARTx USART Instance + * @param StopBits This parameter can be one of the following values: + * @arg @ref LL_USART_STOPBITS_0_5 + * @arg @ref LL_USART_STOPBITS_1 + * @arg @ref LL_USART_STOPBITS_1_5 + * @arg @ref LL_USART_STOPBITS_2 + * @retval None + */ +__STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); +} + +/** + * @brief Retrieve the length of the stop bits + * @rmtoll CR2 STOP LL_USART_GetStopBitsLength + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_STOPBITS_0_5 + * @arg @ref LL_USART_STOPBITS_1 + * @arg @ref LL_USART_STOPBITS_1_5 + * @arg @ref LL_USART_STOPBITS_2 + */ +__STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP)); +} + +/** + * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits) + * @note Call of this function is equivalent to following function call sequence : + * - Data Width configuration using @ref LL_USART_SetDataWidth() function + * - Parity Control and mode configuration using @ref LL_USART_SetParity() function + * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function + * @rmtoll CR1 PS LL_USART_ConfigCharacter\n + * CR1 PCE LL_USART_ConfigCharacter\n + * CR1 M LL_USART_ConfigCharacter\n + * CR2 STOP LL_USART_ConfigCharacter + * @param USARTx USART Instance + * @param DataWidth This parameter can be one of the following values: + * @arg @ref LL_USART_DATAWIDTH_8B + * @arg @ref LL_USART_DATAWIDTH_9B + * @param Parity This parameter can be one of the following values: + * @arg @ref LL_USART_PARITY_NONE + * @arg @ref LL_USART_PARITY_EVEN + * @arg @ref LL_USART_PARITY_ODD + * @param StopBits This parameter can be one of the following values: + * @arg @ref LL_USART_STOPBITS_0_5 + * @arg @ref LL_USART_STOPBITS_1 + * @arg @ref LL_USART_STOPBITS_1_5 + * @arg @ref LL_USART_STOPBITS_2 + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity, + uint32_t StopBits) +{ + MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth); + MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); +} + +/** + * @brief Set Address of the USART node. + * @note This is used in multiprocessor communication during Mute mode or Stop mode, + * for wake up with address mark detection. + * @rmtoll CR2 ADD LL_USART_SetNodeAddress + * @param USARTx USART Instance + * @param NodeAddress 4 bit Address of the USART node. + * @retval None + */ +__STATIC_INLINE void LL_USART_SetNodeAddress(USART_TypeDef *USARTx, uint32_t NodeAddress) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_ADD, (NodeAddress & USART_CR2_ADD)); +} + +/** + * @brief Return 4 bit Address of the USART node as set in ADD field of CR2. + * @note only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant) + * @rmtoll CR2 ADD LL_USART_GetNodeAddress + * @param USARTx USART Instance + * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255) + */ +__STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD)); +} + +/** + * @brief Enable RTS HW Flow Control + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_RTSE); +} + +/** + * @brief Disable RTS HW Flow Control + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE); +} + +/** + * @brief Enable CTS HW Flow Control + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_CTSE); +} + +/** + * @brief Disable CTS HW Flow Control + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE); +} + +/** + * @brief Configure HW Flow Control mode (both CTS and RTS) + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n + * CR3 CTSE LL_USART_SetHWFlowCtrl + * @param USARTx USART Instance + * @param HardwareFlowControl This parameter can be one of the following values: + * @arg @ref LL_USART_HWCONTROL_NONE + * @arg @ref LL_USART_HWCONTROL_RTS + * @arg @ref LL_USART_HWCONTROL_CTS + * @arg @ref LL_USART_HWCONTROL_RTS_CTS + * @retval None + */ +__STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl) +{ + MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl); +} + +/** + * @brief Return HW Flow Control configuration (both CTS and RTS) + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n + * CR3 CTSE LL_USART_GetHWFlowCtrl + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_HWCONTROL_NONE + * @arg @ref LL_USART_HWCONTROL_RTS + * @arg @ref LL_USART_HWCONTROL_CTS + * @arg @ref LL_USART_HWCONTROL_RTS_CTS + */ +__STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE)); +} + +/** + * @brief Enable One bit sampling method + * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_ONEBIT); +} + +/** + * @brief Disable One bit sampling method + * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT); +} + +/** + * @brief Indicate if One bit sampling method is enabled + * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT)); +} + +/** + * @brief Configure USART BRR register for achieving expected Baud Rate value. + * @note Compute and set USARTDIV value in BRR Register (full BRR content) + * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values + * @note Peripheral clock and Baud rate values provided as function parameters should be valid + * (Baud rate value != 0) + * @rmtoll BRR BRR LL_USART_SetBaudRate + * @param USARTx USART Instance + * @param PeriphClk Peripheral Clock + * @param OverSampling This parameter can be one of the following values: + * @arg @ref LL_USART_OVERSAMPLING_16 + * @arg @ref LL_USART_OVERSAMPLING_8 + * @param BaudRate Baud Rate + * @retval None + */ +__STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling, + uint32_t BaudRate) +{ + if (OverSampling == LL_USART_OVERSAMPLING_8) + { + USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate)); + } + else + { + USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate)); + } +} + +/** + * @brief Return current Baud Rate value, according to USARTDIV present in BRR register + * (full BRR content), and to used Peripheral Clock and Oversampling mode values + * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned. + * @rmtoll BRR BRR LL_USART_GetBaudRate + * @param USARTx USART Instance + * @param PeriphClk Peripheral Clock + * @param OverSampling This parameter can be one of the following values: + * @arg @ref LL_USART_OVERSAMPLING_16 + * @arg @ref LL_USART_OVERSAMPLING_8 + * @retval Baud Rate + */ +__STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling) +{ + uint32_t usartdiv = 0x0U; + uint32_t brrresult = 0x0U; + + usartdiv = USARTx->BRR; + + if (OverSampling == LL_USART_OVERSAMPLING_8) + { + if ((usartdiv & 0xFFF7U) != 0U) + { + usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ; + brrresult = (PeriphClk * 2U) / usartdiv; + } + } + else + { + if ((usartdiv & 0xFFFFU) != 0U) + { + brrresult = PeriphClk / usartdiv; + } + } + return (brrresult); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature + * @{ + */ + +/** + * @brief Enable IrDA mode + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll CR3 IREN LL_USART_EnableIrda + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_IREN); +} + +/** + * @brief Disable IrDA mode + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll CR3 IREN LL_USART_DisableIrda + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_IREN); +} + +/** + * @brief Indicate if IrDA mode is enabled + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll CR3 IREN LL_USART_IsEnabledIrda + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN)); +} + +/** + * @brief Configure IrDA Power Mode (Normal or Low Power) + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode + * @param USARTx USART Instance + * @param PowerMode This parameter can be one of the following values: + * @arg @ref LL_USART_IRDA_POWER_NORMAL + * @arg @ref LL_USART_IRDA_POWER_LOW + * @retval None + */ +__STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode) +{ + MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode); +} + +/** + * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power) + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_IRDA_POWER_NORMAL + * @arg @ref LL_USART_PHASE_2EDGE + */ +__STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP)); +} + +/** + * @brief Set Irda prescaler value, used for dividing the USART clock source + * to achieve the Irda Low Power frequency (8 bits value) + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler + * @param USARTx USART Instance + * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) +{ + MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); +} + +/** + * @brief Return Irda prescaler value, used for dividing the USART clock source + * to achieve the Irda Low Power frequency (8 bits value) + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler + * @param USARTx USART Instance + * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF) + */ +__STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature + * @{ + */ + +/** + * @brief Enable Smartcard NACK transmission + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_NACK); +} + +/** + * @brief Disable Smartcard NACK transmission + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_NACK); +} + +/** + * @brief Indicate if Smartcard NACK transmission is enabled + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK)); +} + +/** + * @brief Enable Smartcard mode + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 SCEN LL_USART_EnableSmartcard + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_SCEN); +} + +/** + * @brief Disable Smartcard mode + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 SCEN LL_USART_DisableSmartcard + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN); +} + +/** + * @brief Indicate if Smartcard mode is enabled + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN)); +} + +/** + * @brief Set Smartcard prescaler value, used for dividing the USART clock + * source to provide the SMARTCARD Clock (5 bits value) + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler + * @param USARTx USART Instance + * @param PrescalerValue Value between Min_Data=0 and Max_Data=31 + * @retval None + */ +__STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) +{ + MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); +} + +/** + * @brief Return Smartcard prescaler value, used for dividing the USART clock + * source to provide the SMARTCARD Clock (5 bits value) + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler + * @param USARTx USART Instance + * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31) + */ +__STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); +} + +/** + * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods + * (GT[7:0] bits : Guard time value) + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime + * @param USARTx USART Instance + * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime) +{ + MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_POSITION_GTPR_GT); +} + +/** + * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods + * (GT[7:0] bits : Guard time value) + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime + * @param USARTx USART Instance + * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF) + */ +__STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_POSITION_GTPR_GT); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature + * @{ + */ + +/** + * @brief Enable Single Wire Half-Duplex mode + * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not + * Half-Duplex mode is supported by the USARTx instance. + * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR3, USART_CR3_HDSEL); +} + +/** + * @brief Disable Single Wire Half-Duplex mode + * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not + * Half-Duplex mode is supported by the USARTx instance. + * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL); +} + +/** + * @brief Indicate if Single Wire Half-Duplex mode is enabled + * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not + * Half-Duplex mode is supported by the USARTx instance. + * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature + * @{ + */ + +/** + * @brief Set LIN Break Detection Length + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen + * @param USARTx USART Instance + * @param LINBDLength This parameter can be one of the following values: + * @arg @ref LL_USART_LINBREAK_DETECT_10B + * @arg @ref LL_USART_LINBREAK_DETECT_11B + * @retval None + */ +__STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength) +{ + MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength); +} + +/** + * @brief Return LIN Break Detection Length + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen + * @param USARTx USART Instance + * @retval Returned value can be one of the following values: + * @arg @ref LL_USART_LINBREAK_DETECT_10B + * @arg @ref LL_USART_LINBREAK_DETECT_11B + */ +__STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx) +{ + return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL)); +} + +/** + * @brief Enable LIN mode + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LINEN LL_USART_EnableLIN + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR2, USART_CR2_LINEN); +} + +/** + * @brief Disable LIN mode + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LINEN LL_USART_DisableLIN + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN); +} + +/** + * @brief Indicate if LIN mode is enabled + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services + * @{ + */ + +/** + * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART) + * @note In UART mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - CLKEN bit in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - IREN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * @note Other remaining configurations items related to Asynchronous Mode + * (as Baud Rate, Word length, Parity, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n + * CR2 CLKEN LL_USART_ConfigAsyncMode\n + * CR3 SCEN LL_USART_ConfigAsyncMode\n + * CR3 IREN LL_USART_ConfigAsyncMode\n + * CR3 HDSEL LL_USART_ConfigAsyncMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx) +{ + /* In Asynchronous mode, the following bits must be kept cleared: + - LINEN, CLKEN bits in the USART_CR2 register, + - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); +} + +/** + * @brief Perform basic configuration of USART for enabling use in Synchronous Mode + * @note In Synchronous mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - IREN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * This function also sets the USART in Synchronous mode. + * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not + * Synchronous mode is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function + * @note Other remaining configurations items related to Synchronous Mode + * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n + * CR2 CLKEN LL_USART_ConfigSyncMode\n + * CR3 SCEN LL_USART_ConfigSyncMode\n + * CR3 IREN LL_USART_ConfigSyncMode\n + * CR3 HDSEL LL_USART_ConfigSyncMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx) +{ + /* In Synchronous mode, the following bits must be kept cleared: + - LINEN bit in the USART_CR2 register, + - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); + /* set the UART/USART in Synchronous mode */ + SET_BIT(USARTx->CR2, USART_CR2_CLKEN); +} + +/** + * @brief Perform basic configuration of USART for enabling use in LIN Mode + * @note In LIN mode, the following bits must be kept cleared: + * - STOP and CLKEN bits in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - IREN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * This function also set the UART/USART in LIN mode. + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function + * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function + * @note Other remaining configurations items related to LIN Mode + * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using + * dedicated functions + * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n + * CR2 STOP LL_USART_ConfigLINMode\n + * CR2 LINEN LL_USART_ConfigLINMode\n + * CR3 IREN LL_USART_ConfigLINMode\n + * CR3 SCEN LL_USART_ConfigLINMode\n + * CR3 HDSEL LL_USART_ConfigLINMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx) +{ + /* In LIN mode, the following bits must be kept cleared: + - STOP and CLKEN bits in the USART_CR2 register, + - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL)); + /* Set the UART/USART in LIN mode */ + SET_BIT(USARTx->CR2, USART_CR2_LINEN); +} + +/** + * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode + * @note In Half Duplex mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - CLKEN bit in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - IREN bit in the USART_CR3 register, + * This function also sets the UART/USART in Half Duplex mode. + * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not + * Half-Duplex mode is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function + * @note Other remaining configurations items related to Half Duplex Mode + * (as Baud Rate, Word length, Parity, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n + * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n + * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n + * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n + * CR3 IREN LL_USART_ConfigHalfDuplexMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx) +{ + /* In Half Duplex mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN)); + /* set the UART/USART in Half Duplex mode */ + SET_BIT(USARTx->CR3, USART_CR3_HDSEL); +} + +/** + * @brief Perform basic configuration of USART for enabling use in Smartcard Mode + * @note In Smartcard mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - IREN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * This function also configures Stop bits to 1.5 bits and + * sets the USART in Smartcard mode (SCEN bit). + * Clock Output is also enabled (CLKEN). + * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not + * Smartcard feature is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function + * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function + * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function + * @note Other remaining configurations items related to Smartcard Mode + * (as Baud Rate, Word length, Parity, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n + * CR2 STOP LL_USART_ConfigSmartcardMode\n + * CR2 CLKEN LL_USART_ConfigSmartcardMode\n + * CR3 HDSEL LL_USART_ConfigSmartcardMode\n + * CR3 SCEN LL_USART_ConfigSmartcardMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx) +{ + /* In Smartcard mode, the following bits must be kept cleared: + - LINEN bit in the USART_CR2 register, + - IREN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); + /* Configure Stop bits to 1.5 bits */ + /* Synchronous mode is activated by default */ + SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN)); + /* set the UART/USART in Smartcard mode */ + SET_BIT(USARTx->CR3, USART_CR3_SCEN); +} + +/** + * @brief Perform basic configuration of USART for enabling use in Irda Mode + * @note In IRDA mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - STOP and CLKEN bits in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * This function also sets the UART/USART in IRDA mode (IREN bit). + * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not + * IrDA feature is supported by the USARTx instance. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function + * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function + * @note Other remaining configurations items related to Irda Mode + * (as Baud Rate, Word length, Power mode, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n + * CR2 CLKEN LL_USART_ConfigIrdaMode\n + * CR2 STOP LL_USART_ConfigIrdaMode\n + * CR3 SCEN LL_USART_ConfigIrdaMode\n + * CR3 HDSEL LL_USART_ConfigIrdaMode\n + * CR3 IREN LL_USART_ConfigIrdaMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx) +{ + /* In IRDA mode, the following bits must be kept cleared: + - LINEN, STOP and CLKEN bits in the USART_CR2 register, + - SCEN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); + /* set the UART/USART in IRDA mode */ + SET_BIT(USARTx->CR3, USART_CR3_IREN); +} + +/** + * @brief Perform basic configuration of USART for enabling use in Multi processor Mode + * (several USARTs connected in a network, one of the USARTs can be the master, + * its TX output connected to the RX inputs of the other slaves USARTs). + * @note In MultiProcessor mode, the following bits must be kept cleared: + * - LINEN bit in the USART_CR2 register, + * - CLKEN bit in the USART_CR2 register, + * - SCEN bit in the USART_CR3 register, + * - IREN bit in the USART_CR3 register, + * - HDSEL bit in the USART_CR3 register. + * @note Call of this function is equivalent to following function call sequence : + * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function + * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function + * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function + * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function + * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function + * @note Other remaining configurations items related to Multi processor Mode + * (as Baud Rate, Wake Up Method, Node address, ...) should be set using + * dedicated functions + * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n + * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n + * CR3 SCEN LL_USART_ConfigMultiProcessMode\n + * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n + * CR3 IREN LL_USART_ConfigMultiProcessMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx) +{ + /* In Multi Processor mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_FLAG_Management FLAG_Management + * @{ + */ + +/** + * @brief Check if the USART Parity Error Flag is set or not + * @rmtoll SR PE LL_USART_IsActiveFlag_PE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_PE) == (USART_SR_PE)); +} + +/** + * @brief Check if the USART Framing Error Flag is set or not + * @rmtoll SR FE LL_USART_IsActiveFlag_FE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_FE) == (USART_SR_FE)); +} + +/** + * @brief Check if the USART Noise error detected Flag is set or not + * @rmtoll SR NF LL_USART_IsActiveFlag_NE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_NE) == (USART_SR_NE)); +} + +/** + * @brief Check if the USART OverRun Error Flag is set or not + * @rmtoll SR ORE LL_USART_IsActiveFlag_ORE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_ORE) == (USART_SR_ORE)); +} + +/** + * @brief Check if the USART IDLE line detected Flag is set or not + * @rmtoll SR IDLE LL_USART_IsActiveFlag_IDLE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_IDLE) == (USART_SR_IDLE)); +} + +/** + * @brief Check if the USART Read Data Register Not Empty Flag is set or not + * @rmtoll SR RXNE LL_USART_IsActiveFlag_RXNE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_RXNE) == (USART_SR_RXNE)); +} + +/** + * @brief Check if the USART Transmission Complete Flag is set or not + * @rmtoll SR TC LL_USART_IsActiveFlag_TC + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_TC) == (USART_SR_TC)); +} + +/** + * @brief Check if the USART Transmit Data Register Empty Flag is set or not + * @rmtoll SR TXE LL_USART_IsActiveFlag_TXE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_TXE) == (USART_SR_TXE)); +} + +/** + * @brief Check if the USART LIN Break Detection Flag is set or not + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll SR LBD LL_USART_IsActiveFlag_LBD + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_LBD) == (USART_SR_LBD)); +} + +/** + * @brief Check if the USART CTS Flag is set or not + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll SR CTS LL_USART_IsActiveFlag_nCTS + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->SR, USART_SR_CTS) == (USART_SR_CTS)); +} + +/** + * @brief Check if the USART Send Break Flag is set or not + * @rmtoll CR1 SBK LL_USART_IsActiveFlag_SBK + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_SBK) == (USART_CR1_SBK)); +} + +/** + * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not + * @rmtoll CR1 RWU LL_USART_IsActiveFlag_RWU + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_RWU) == (USART_CR1_RWU)); +} + +/** + * @brief Clear Parity Error Flag + * @note Clearing this flag is done by a read access to the USARTx_SR + * register followed by a read access to the USARTx_DR register. + * @note Please also consider that when clearing this flag, other flags as + * NE, FE, ORE, IDLE would also be cleared. + * @rmtoll SR PE LL_USART_ClearFlag_PE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx) +{ + __IO uint32_t tmpreg; + tmpreg = USARTx->SR; + (void) tmpreg; + tmpreg = USARTx->DR; + (void) tmpreg; +} + +/** + * @brief Clear Framing Error Flag + * @note Clearing this flag is done by a read access to the USARTx_SR + * register followed by a read access to the USARTx_DR register. + * @note Please also consider that when clearing this flag, other flags as + * PE, NE, ORE, IDLE would also be cleared. + * @rmtoll SR FE LL_USART_ClearFlag_FE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx) +{ + __IO uint32_t tmpreg; + tmpreg = USARTx->SR; + (void) tmpreg; + tmpreg = USARTx->DR; + (void) tmpreg; +} + +/** + * @brief Clear Noise detected Flag + * @note Clearing this flag is done by a read access to the USARTx_SR + * register followed by a read access to the USARTx_DR register. + * @note Please also consider that when clearing this flag, other flags as + * PE, FE, ORE, IDLE would also be cleared. + * @rmtoll SR NF LL_USART_ClearFlag_NE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx) +{ + __IO uint32_t tmpreg; + tmpreg = USARTx->SR; + (void) tmpreg; + tmpreg = USARTx->DR; + (void) tmpreg; +} + +/** + * @brief Clear OverRun Error Flag + * @note Clearing this flag is done by a read access to the USARTx_SR + * register followed by a read access to the USARTx_DR register. + * @note Please also consider that when clearing this flag, other flags as + * PE, NE, FE, IDLE would also be cleared. + * @rmtoll SR ORE LL_USART_ClearFlag_ORE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx) +{ + __IO uint32_t tmpreg; + tmpreg = USARTx->SR; + (void) tmpreg; + tmpreg = USARTx->DR; + (void) tmpreg; +} + +/** + * @brief Clear IDLE line detected Flag + * @note Clearing this flag is done by a read access to the USARTx_SR + * register followed by a read access to the USARTx_DR register. + * @note Please also consider that when clearing this flag, other flags as + * PE, NE, FE, ORE would also be cleared. + * @rmtoll SR IDLE LL_USART_ClearFlag_IDLE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx) +{ + __IO uint32_t tmpreg; + tmpreg = USARTx->SR; + (void) tmpreg; + tmpreg = USARTx->DR; + (void) tmpreg; +} + +/** + * @brief Clear Transmission Complete Flag + * @rmtoll SR TC LL_USART_ClearFlag_TC + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx) +{ + WRITE_REG(USARTx->SR, ~(USART_SR_TC)); +} + +/** + * @brief Clear RX Not Empty Flag + * @rmtoll SR RXNE LL_USART_ClearFlag_RXNE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_RXNE(USART_TypeDef *USARTx) +{ + WRITE_REG(USARTx->SR, ~(USART_SR_RXNE)); +} + +/** + * @brief Clear LIN Break Detection Flag + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll SR LBD LL_USART_ClearFlag_LBD + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx) +{ + WRITE_REG(USARTx->SR, ~(USART_SR_LBD)); +} + +/** + * @brief Clear CTS Interrupt Flag + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll SR CTS LL_USART_ClearFlag_nCTS + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx) +{ + WRITE_REG(USARTx->SR, ~(USART_SR_CTS)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_IT_Management IT_Management + * @{ + */ + +/** + * @brief Enable IDLE Interrupt + * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_IDLEIE); +} + +/** + * @brief Enable RX Not Empty Interrupt + * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RXNEIE); +} + +/** + * @brief Enable Transmission Complete Interrupt + * @rmtoll CR1 TCIE LL_USART_EnableIT_TC + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TCIE); +} + +/** + * @brief Enable TX Empty Interrupt + * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TXEIE); +} + +/** + * @brief Enable Parity Error Interrupt + * @rmtoll CR1 PEIE LL_USART_EnableIT_PE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_PEIE); +} + +/** + * @brief Enable LIN Break Detection Interrupt + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR2, USART_CR2_LBDIE); +} + +/** + * @brief Enable Error Interrupt + * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing + * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). + * 0: Interrupt is inhibited + * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. + * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_EIE); +} + +/** + * @brief Enable CTS Interrupt + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_CTSIE); +} + +/** + * @brief Disable IDLE Interrupt + * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE); +} + +/** + * @brief Disable RX Not Empty Interrupt + * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE); +} + +/** + * @brief Disable Transmission Complete Interrupt + * @rmtoll CR1 TCIE LL_USART_DisableIT_TC + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE); +} + +/** + * @brief Disable TX Empty Interrupt + * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE); +} + +/** + * @brief Disable Parity Error Interrupt + * @rmtoll CR1 PEIE LL_USART_DisableIT_PE + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE); +} + +/** + * @brief Disable LIN Break Detection Interrupt + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE); +} + +/** + * @brief Disable Error Interrupt + * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing + * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). + * 0: Interrupt is inhibited + * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. + * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_EIE); +} + +/** + * @brief Disable CTS Interrupt + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE); +} + +/** + * @brief Check if the USART IDLE Interrupt source is enabled or disabled. + * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE)); +} + +/** + * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled. + * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE)); +} + +/** + * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled. + * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE)); +} + +/** + * @brief Check if the USART TX Empty Interrupt is enabled or disabled. + * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE)); +} + +/** + * @brief Check if the USART Parity Error Interrupt is enabled or disabled. + * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE)); +} + +/** + * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled. + * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not + * LIN feature is supported by the USARTx instance. + * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE)); +} + +/** + * @brief Check if the USART Error Interrupt is enabled or disabled. + * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE)); +} + +/** + * @brief Check if the USART CTS Interrupt is enabled or disabled. + * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not + * Hardware Flow control feature is supported by the USARTx instance. + * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_DMA_Management DMA_Management + * @{ + */ + +/** + * @brief Enable DMA Mode for reception + * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAR); +} + +/** + * @brief Disable DMA Mode for reception + * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR); +} + +/** + * @brief Check if DMA Mode is enabled for reception + * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR)); +} + +/** + * @brief Enable DMA Mode for transmission + * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx) +{ + ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAT); +} + +/** + * @brief Disable DMA Mode for transmission + * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx) +{ + ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT); +} + +/** + * @brief Check if DMA Mode is enabled for transmission + * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX + * @param USARTx USART Instance + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx) +{ + return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT)); +} + +/** + * @brief Get the data register address used for DMA transfer + * @rmtoll DR DR LL_USART_DMA_GetRegAddr + * @note Address of Data Register is valid for both Transmit and Receive transfers. + * @param USARTx USART Instance + * @retval Address of data register + */ +__STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx) +{ + /* return address of DR register */ + return ((uint32_t) &(USARTx->DR)); +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Data_Management Data_Management + * @{ + */ + +/** + * @brief Read Receiver Data register (Receive Data value, 8 bits) + * @rmtoll DR DR LL_USART_ReceiveData8 + * @param USARTx USART Instance + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx) +{ + return (uint8_t)(READ_BIT(USARTx->DR, USART_DR_DR)); +} + +/** + * @brief Read Receiver Data register (Receive Data value, 9 bits) + * @rmtoll DR DR LL_USART_ReceiveData9 + * @param USARTx USART Instance + * @retval Value between Min_Data=0x00 and Max_Data=0x1FF + */ +__STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx) +{ + return (uint16_t)(READ_BIT(USARTx->DR, USART_DR_DR)); +} + +/** + * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits) + * @rmtoll DR DR LL_USART_TransmitData8 + * @param USARTx USART Instance + * @param Value between Min_Data=0x00 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value) +{ + USARTx->DR = Value; +} + +/** + * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits) + * @rmtoll DR DR LL_USART_TransmitData9 + * @param USARTx USART Instance + * @param Value between Min_Data=0x00 and Max_Data=0x1FF + * @retval None + */ +__STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value) +{ + USARTx->DR = Value & 0x1FFU; +} + +/** + * @} + */ + +/** @defgroup USART_LL_EF_Execution Execution + * @{ + */ + +/** + * @brief Request Break sending + * @rmtoll CR1 SBK LL_USART_RequestBreakSending + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR1, USART_CR1_SBK); +} + +/** + * @brief Put USART in Mute mode + * @rmtoll CR1 RWU LL_USART_RequestEnterMuteMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx) +{ + SET_BIT(USARTx->CR1, USART_CR1_RWU); +} + +/** + * @brief Put USART in Active mode + * @rmtoll CR1 RWU LL_USART_RequestExitMuteMode + * @param USARTx USART Instance + * @retval None + */ +__STATIC_INLINE void LL_USART_RequestExitMuteMode(USART_TypeDef *USARTx) +{ + CLEAR_BIT(USARTx->CR1, USART_CR1_RWU); +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup USART_LL_EF_Init Initialization and de-initialization functions + * @{ + */ +ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx); +ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct); +void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct); +ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct); +void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct); +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_USART_H */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h index a7114cd..a50d49d 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h @@ -1,536 +1,536 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usb.h - * @author MCD Application Team - * @brief Header file of USB Low Layer HAL module. - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_USB_H -#define STM32F4xx_LL_USB_H - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup USB_LL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief USB Mode definition - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -typedef enum -{ - USB_DEVICE_MODE = 0, - USB_HOST_MODE = 1, - USB_DRD_MODE = 2 -} USB_OTG_ModeTypeDef; - -/** - * @brief URB States definition - */ -typedef enum -{ - URB_IDLE = 0, - URB_DONE, - URB_NOTREADY, - URB_NYET, - URB_ERROR, - URB_STALL -} USB_OTG_URBStateTypeDef; - -/** - * @brief Host channel States definition - */ -typedef enum -{ - HC_IDLE = 0, - HC_XFRC, - HC_HALTED, - HC_NAK, - HC_NYET, - HC_STALL, - HC_XACTERR, - HC_BBLERR, - HC_DATATGLERR -} USB_OTG_HCStateTypeDef; - - -/** - * @brief USB Instance Initialization Structure definition - */ -typedef struct -{ - uint32_t dev_endpoints; /*!< Device Endpoints number. - This parameter depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t Host_channels; /*!< Host Channels number. - This parameter Depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t speed; /*!< USB Core speed. - This parameter can be any value of @ref PCD_Speed/HCD_Speed - (HCD_SPEED_xxx, HCD_SPEED_xxx) */ - - uint32_t dma_enable; /*!< Enable or disable of the USB embedded DMA used only for OTG HS. */ - - uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size. */ - - uint32_t phy_itface; /*!< Select the used PHY interface. - This parameter can be any value of @ref PCD_PHY_Module/HCD_PHY_Module */ - - uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal. */ - - uint32_t low_power_enable; /*!< Enable or disable the low power mode. */ - - uint32_t lpm_enable; /*!< Enable or disable Link Power Management. */ - - uint32_t battery_charging_enable; /*!< Enable or disable Battery charging. */ - - uint32_t vbus_sensing_enable; /*!< Enable or disable the VBUS Sensing feature. */ - - uint32_t use_dedicated_ep1; /*!< Enable or disable the use of the dedicated EP1 interrupt. */ - - uint32_t use_external_vbus; /*!< Enable or disable the use of the external VBUS. */ - -} USB_OTG_CfgTypeDef; - -typedef struct -{ - uint8_t num; /*!< Endpoint number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t is_stall; /*!< Endpoint stall condition - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t is_iso_incomplete; /*!< Endpoint isoc condition - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t type; /*!< Endpoint type - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint8_t data_pid_start; /*!< Initial data PID - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t even_odd_frame; /*!< IFrame parity - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint16_t tx_fifo_num; /*!< Transmission FIFO number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t maxpacket; /*!< Endpoint Max packet size - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address */ - - uint32_t xfer_len; /*!< Current transfer length */ - - uint32_t xfer_size; /*!< requested transfer size */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */ -} USB_OTG_EPTypeDef; - -typedef struct -{ - uint8_t dev_addr; /*!< USB device address. - This parameter must be a number between Min_Data = 1 and Max_Data = 255 */ - - uint8_t ch_num; /*!< Host channel number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_num; /*!< Endpoint number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t speed; /*!< USB Host Channel speed. - This parameter can be any value of @ref HCD_Device_Speed: - (HCD_DEVICE_SPEED_xxx) */ - - uint8_t do_ping; /*!< Enable or disable the use of the PING protocol for HS mode. */ - - uint8_t process_ping; /*!< Execute the PING protocol for HS mode. */ - - uint8_t ep_type; /*!< Endpoint Type. - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint16_t max_packet; /*!< Endpoint Max packet size. - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t data_pid; /*!< Initial data PID. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer. */ - - uint32_t XferSize; /*!< OTG Channel transfer size. */ - - uint32_t xfer_len; /*!< Current transfer length. */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer. */ - - uint8_t toggle_in; /*!< IN transfer current toggle flag. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t toggle_out; /*!< OUT transfer current toggle flag - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address. */ - - uint32_t ErrCnt; /*!< Host channel error count. */ - - USB_OTG_URBStateTypeDef urb_state; /*!< URB state. - This parameter can be any value of @ref USB_OTG_URBStateTypeDef */ - - USB_OTG_HCStateTypeDef state; /*!< Host Channel state. - This parameter can be any value of @ref USB_OTG_HCStateTypeDef */ -} USB_OTG_HCTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @defgroup USB_OTG_CORE VERSION ID - * @{ - */ -#define USB_OTG_CORE_ID_300A 0x4F54300AU -#define USB_OTG_CORE_ID_310A 0x4F54310AU -/** - * @} - */ - -/** @defgroup USB_Core_Mode_ USB Core Mode - * @{ - */ -#define USB_OTG_MODE_DEVICE 0U -#define USB_OTG_MODE_HOST 1U -#define USB_OTG_MODE_DRD 2U -/** - * @} - */ - -/** @defgroup USB_LL Device Speed - * @{ - */ -#define USBD_HS_SPEED 0U -#define USBD_HSINFS_SPEED 1U -#define USBH_HS_SPEED 0U -#define USBD_FS_SPEED 2U -#define USBH_FSLS_SPEED 1U -/** - * @} - */ - -/** @defgroup USB_LL_Core_Speed USB Low Layer Core Speed - * @{ - */ -#define USB_OTG_SPEED_HIGH 0U -#define USB_OTG_SPEED_HIGH_IN_FULL 1U -#define USB_OTG_SPEED_FULL 3U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY USB Low Layer Core PHY - * @{ - */ -#define USB_OTG_ULPI_PHY 1U -#define USB_OTG_EMBEDDED_PHY 2U -/** - * @} - */ - -/** @defgroup USB_LL_Turnaround_Timeout Turnaround Timeout Value - * @{ - */ -#ifndef USBD_HS_TRDT_VALUE -#define USBD_HS_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -#ifndef USBD_FS_TRDT_VALUE -#define USBD_FS_TRDT_VALUE 5U -#define USBD_DEFAULT_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -/** - * @} - */ - -/** @defgroup USB_LL_Core_MPS USB Low Layer Core MPS - * @{ - */ -#define USB_OTG_HS_MAX_PACKET_SIZE 512U -#define USB_OTG_FS_MAX_PACKET_SIZE 64U -#define USB_OTG_MAX_EP0_SIZE 64U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY_Frequency USB Low Layer Core PHY Frequency - * @{ - */ -#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ (0U << 1) -#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ (1U << 1) -#define DSTS_ENUMSPD_FS_PHY_48MHZ (3U << 1) -/** - * @} - */ - -/** @defgroup USB_LL_CORE_Frame_Interval USB Low Layer Core Frame Interval - * @{ - */ -#define DCFG_FRAME_INTERVAL_80 0U -#define DCFG_FRAME_INTERVAL_85 1U -#define DCFG_FRAME_INTERVAL_90 2U -#define DCFG_FRAME_INTERVAL_95 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP0_MPS USB Low Layer EP0 MPS - * @{ - */ -#define EP_MPS_64 0U -#define EP_MPS_32 1U -#define EP_MPS_16 2U -#define EP_MPS_8 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Speed USB Low Layer EP Speed - * @{ - */ -#define EP_SPEED_LOW 0U -#define EP_SPEED_FULL 1U -#define EP_SPEED_HIGH 2U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Type USB Low Layer EP Type - * @{ - */ -#define EP_TYPE_CTRL 0U -#define EP_TYPE_ISOC 1U -#define EP_TYPE_BULK 2U -#define EP_TYPE_INTR 3U -#define EP_TYPE_MSK 3U -/** - * @} - */ - -/** @defgroup USB_LL_STS_Defines USB Low Layer STS Defines - * @{ - */ -#define STS_GOUT_NAK 1U -#define STS_DATA_UPDT 2U -#define STS_XFER_COMP 3U -#define STS_SETUP_COMP 4U -#define STS_SETUP_UPDT 6U -/** - * @} - */ - -/** @defgroup USB_LL_HCFG_SPEED_Defines USB Low Layer HCFG Speed Defines - * @{ - */ -#define HCFG_30_60_MHZ 0U -#define HCFG_48_MHZ 1U -#define HCFG_6_MHZ 2U -/** - * @} - */ - -/** @defgroup USB_LL_HPRT0_PRTSPD_SPEED_Defines USB Low Layer HPRT0 PRTSPD Speed Defines - * @{ - */ -#define HPRT0_PRTSPD_HIGH_SPEED 0U -#define HPRT0_PRTSPD_FULL_SPEED 1U -#define HPRT0_PRTSPD_LOW_SPEED 2U -/** - * @} - */ - -#define HCCHAR_CTRL 0U -#define HCCHAR_ISOC 1U -#define HCCHAR_BULK 2U -#define HCCHAR_INTR 3U - -#define HC_PID_DATA0 0U -#define HC_PID_DATA2 1U -#define HC_PID_DATA1 2U -#define HC_PID_SETUP 3U - -#define GRXSTS_PKTSTS_IN 2U -#define GRXSTS_PKTSTS_IN_XFER_COMP 3U -#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U -#define GRXSTS_PKTSTS_CH_HALTED 7U - -#define TEST_J 1U -#define TEST_K 2U -#define TEST_SE0_NAK 3U -#define TEST_PACKET 4U -#define TEST_FORCE_EN 5U - -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_PCGCCTL_BASE) -#define USBx_HPRT0 *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_HOST_PORT_BASE) - -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)(USBx_BASE + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_DFIFO(i) *(__IO uint32_t *)(USBx_BASE + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) - -#define USBx_HOST ((USB_OTG_HostTypeDef *)(USBx_BASE + USB_OTG_HOST_BASE)) -#define USBx_HC(i) ((USB_OTG_HostChannelTypeDef *)(USBx_BASE\ - + USB_OTG_HOST_CHANNEL_BASE\ - + ((i) * USB_OTG_HOST_CHANNEL_SIZE))) - -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#define EP_ADDR_MSK 0xFU - -#ifndef USE_USB_DOUBLE_BUFFER -#define USE_USB_DOUBLE_BUFFER 1U -#endif /* USE_USB_DOUBLE_BUFFER */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USB_LL_Exported_Macros USB Low Layer Exported Macros - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_MASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK &= ~(__INTERRUPT__)) -#define USB_UNMASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK |= (__INTERRUPT__)) - -#define CLEAR_IN_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_INEP(__EPNUM__)->DIEPINT = (__INTERRUPT__)) -#define CLEAR_OUT_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_OUTEP(__EPNUM__)->DOEPINT = (__INTERRUPT__)) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USB_LL_Exported_Functions USB Low Layer Exported Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, uint32_t hclk, uint8_t speed); -HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode); -HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed); -HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num); -HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, - uint8_t ch_ep_num, uint16_t len, uint8_t dma); - -void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len); -HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPStopXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address); -HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup); -uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt); - -HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq); -HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state); -uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, uint8_t speed, - uint8_t ep_type, uint16_t mps); -HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, - USB_OTG_HCTypeDef *hc, uint8_t dma); - -uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num); -HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num); -HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - - -#endif /* STM32F4xx_LL_USB_H */ +/** + ****************************************************************************** + * @file stm32f4xx_ll_usb.h + * @author MCD Application Team + * @brief Header file of USB Low Layer HAL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32F4xx_LL_USB_H +#define STM32F4xx_LL_USB_H + +#ifdef __cplusplus +extern "C" { +#endif /* __cplusplus */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal_def.h" + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup USB_LL + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief USB Mode definition + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) + +typedef enum +{ + USB_DEVICE_MODE = 0, + USB_HOST_MODE = 1, + USB_DRD_MODE = 2 +} USB_OTG_ModeTypeDef; + +/** + * @brief URB States definition + */ +typedef enum +{ + URB_IDLE = 0, + URB_DONE, + URB_NOTREADY, + URB_NYET, + URB_ERROR, + URB_STALL +} USB_OTG_URBStateTypeDef; + +/** + * @brief Host channel States definition + */ +typedef enum +{ + HC_IDLE = 0, + HC_XFRC, + HC_HALTED, + HC_NAK, + HC_NYET, + HC_STALL, + HC_XACTERR, + HC_BBLERR, + HC_DATATGLERR +} USB_OTG_HCStateTypeDef; + + +/** + * @brief USB Instance Initialization Structure definition + */ +typedef struct +{ + uint32_t dev_endpoints; /*!< Device Endpoints number. + This parameter depends on the used USB core. + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint32_t Host_channels; /*!< Host Channels number. + This parameter Depends on the used USB core. + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint32_t speed; /*!< USB Core speed. + This parameter can be any value of @ref PCD_Speed/HCD_Speed + (HCD_SPEED_xxx, HCD_SPEED_xxx) */ + + uint32_t dma_enable; /*!< Enable or disable of the USB embedded DMA used only for OTG HS. */ + + uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size. */ + + uint32_t phy_itface; /*!< Select the used PHY interface. + This parameter can be any value of @ref PCD_PHY_Module/HCD_PHY_Module */ + + uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal. */ + + uint32_t low_power_enable; /*!< Enable or disable the low power mode. */ + + uint32_t lpm_enable; /*!< Enable or disable Link Power Management. */ + + uint32_t battery_charging_enable; /*!< Enable or disable Battery charging. */ + + uint32_t vbus_sensing_enable; /*!< Enable or disable the VBUS Sensing feature. */ + + uint32_t use_dedicated_ep1; /*!< Enable or disable the use of the dedicated EP1 interrupt. */ + + uint32_t use_external_vbus; /*!< Enable or disable the use of the external VBUS. */ + +} USB_OTG_CfgTypeDef; + +typedef struct +{ + uint8_t num; /*!< Endpoint number + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint8_t is_in; /*!< Endpoint direction + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t is_stall; /*!< Endpoint stall condition + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t is_iso_incomplete; /*!< Endpoint isoc condition + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t type; /*!< Endpoint type + This parameter can be any value of @ref USB_LL_EP_Type */ + + uint8_t data_pid_start; /*!< Initial data PID + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t even_odd_frame; /*!< IFrame parity + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint16_t tx_fifo_num; /*!< Transmission FIFO number + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint32_t maxpacket; /*!< Endpoint Max packet size + This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ + + uint8_t *xfer_buff; /*!< Pointer to transfer buffer */ + + uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address */ + + uint32_t xfer_len; /*!< Current transfer length */ + + uint32_t xfer_size; /*!< requested transfer size */ + + uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */ +} USB_OTG_EPTypeDef; + +typedef struct +{ + uint8_t dev_addr; /*!< USB device address. + This parameter must be a number between Min_Data = 1 and Max_Data = 255 */ + + uint8_t ch_num; /*!< Host channel number. + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint8_t ep_num; /*!< Endpoint number. + This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ + + uint8_t ep_is_in; /*!< Endpoint direction + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t speed; /*!< USB Host Channel speed. + This parameter can be any value of @ref HCD_Device_Speed: + (HCD_DEVICE_SPEED_xxx) */ + + uint8_t do_ping; /*!< Enable or disable the use of the PING protocol for HS mode. */ + + uint8_t process_ping; /*!< Execute the PING protocol for HS mode. */ + + uint8_t ep_type; /*!< Endpoint Type. + This parameter can be any value of @ref USB_LL_EP_Type */ + + uint16_t max_packet; /*!< Endpoint Max packet size. + This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ + + uint8_t data_pid; /*!< Initial data PID. + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t *xfer_buff; /*!< Pointer to transfer buffer. */ + + uint32_t XferSize; /*!< OTG Channel transfer size. */ + + uint32_t xfer_len; /*!< Current transfer length. */ + + uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer. */ + + uint8_t toggle_in; /*!< IN transfer current toggle flag. + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint8_t toggle_out; /*!< OUT transfer current toggle flag + This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ + + uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address. */ + + uint32_t ErrCnt; /*!< Host channel error count. */ + + USB_OTG_URBStateTypeDef urb_state; /*!< URB state. + This parameter can be any value of @ref USB_OTG_URBStateTypeDef */ + + USB_OTG_HCStateTypeDef state; /*!< Host Channel state. + This parameter can be any value of @ref USB_OTG_HCStateTypeDef */ +} USB_OTG_HCTypeDef; +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup PCD_Exported_Constants PCD Exported Constants + * @{ + */ + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** @defgroup USB_OTG_CORE VERSION ID + * @{ + */ +#define USB_OTG_CORE_ID_300A 0x4F54300AU +#define USB_OTG_CORE_ID_310A 0x4F54310AU +/** + * @} + */ + +/** @defgroup USB_Core_Mode_ USB Core Mode + * @{ + */ +#define USB_OTG_MODE_DEVICE 0U +#define USB_OTG_MODE_HOST 1U +#define USB_OTG_MODE_DRD 2U +/** + * @} + */ + +/** @defgroup USB_LL Device Speed + * @{ + */ +#define USBD_HS_SPEED 0U +#define USBD_HSINFS_SPEED 1U +#define USBH_HS_SPEED 0U +#define USBD_FS_SPEED 2U +#define USBH_FSLS_SPEED 1U +/** + * @} + */ + +/** @defgroup USB_LL_Core_Speed USB Low Layer Core Speed + * @{ + */ +#define USB_OTG_SPEED_HIGH 0U +#define USB_OTG_SPEED_HIGH_IN_FULL 1U +#define USB_OTG_SPEED_FULL 3U +/** + * @} + */ + +/** @defgroup USB_LL_Core_PHY USB Low Layer Core PHY + * @{ + */ +#define USB_OTG_ULPI_PHY 1U +#define USB_OTG_EMBEDDED_PHY 2U +/** + * @} + */ + +/** @defgroup USB_LL_Turnaround_Timeout Turnaround Timeout Value + * @{ + */ +#ifndef USBD_HS_TRDT_VALUE +#define USBD_HS_TRDT_VALUE 9U +#endif /* USBD_HS_TRDT_VALUE */ +#ifndef USBD_FS_TRDT_VALUE +#define USBD_FS_TRDT_VALUE 5U +#define USBD_DEFAULT_TRDT_VALUE 9U +#endif /* USBD_HS_TRDT_VALUE */ +/** + * @} + */ + +/** @defgroup USB_LL_Core_MPS USB Low Layer Core MPS + * @{ + */ +#define USB_OTG_HS_MAX_PACKET_SIZE 512U +#define USB_OTG_FS_MAX_PACKET_SIZE 64U +#define USB_OTG_MAX_EP0_SIZE 64U +/** + * @} + */ + +/** @defgroup USB_LL_Core_PHY_Frequency USB Low Layer Core PHY Frequency + * @{ + */ +#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ (0U << 1) +#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ (1U << 1) +#define DSTS_ENUMSPD_FS_PHY_48MHZ (3U << 1) +/** + * @} + */ + +/** @defgroup USB_LL_CORE_Frame_Interval USB Low Layer Core Frame Interval + * @{ + */ +#define DCFG_FRAME_INTERVAL_80 0U +#define DCFG_FRAME_INTERVAL_85 1U +#define DCFG_FRAME_INTERVAL_90 2U +#define DCFG_FRAME_INTERVAL_95 3U +/** + * @} + */ + +/** @defgroup USB_LL_EP0_MPS USB Low Layer EP0 MPS + * @{ + */ +#define EP_MPS_64 0U +#define EP_MPS_32 1U +#define EP_MPS_16 2U +#define EP_MPS_8 3U +/** + * @} + */ + +/** @defgroup USB_LL_EP_Speed USB Low Layer EP Speed + * @{ + */ +#define EP_SPEED_LOW 0U +#define EP_SPEED_FULL 1U +#define EP_SPEED_HIGH 2U +/** + * @} + */ + +/** @defgroup USB_LL_EP_Type USB Low Layer EP Type + * @{ + */ +#define EP_TYPE_CTRL 0U +#define EP_TYPE_ISOC 1U +#define EP_TYPE_BULK 2U +#define EP_TYPE_INTR 3U +#define EP_TYPE_MSK 3U +/** + * @} + */ + +/** @defgroup USB_LL_STS_Defines USB Low Layer STS Defines + * @{ + */ +#define STS_GOUT_NAK 1U +#define STS_DATA_UPDT 2U +#define STS_XFER_COMP 3U +#define STS_SETUP_COMP 4U +#define STS_SETUP_UPDT 6U +/** + * @} + */ + +/** @defgroup USB_LL_HCFG_SPEED_Defines USB Low Layer HCFG Speed Defines + * @{ + */ +#define HCFG_30_60_MHZ 0U +#define HCFG_48_MHZ 1U +#define HCFG_6_MHZ 2U +/** + * @} + */ + +/** @defgroup USB_LL_HPRT0_PRTSPD_SPEED_Defines USB Low Layer HPRT0 PRTSPD Speed Defines + * @{ + */ +#define HPRT0_PRTSPD_HIGH_SPEED 0U +#define HPRT0_PRTSPD_FULL_SPEED 1U +#define HPRT0_PRTSPD_LOW_SPEED 2U +/** + * @} + */ + +#define HCCHAR_CTRL 0U +#define HCCHAR_ISOC 1U +#define HCCHAR_BULK 2U +#define HCCHAR_INTR 3U + +#define HC_PID_DATA0 0U +#define HC_PID_DATA2 1U +#define HC_PID_DATA1 2U +#define HC_PID_SETUP 3U + +#define GRXSTS_PKTSTS_IN 2U +#define GRXSTS_PKTSTS_IN_XFER_COMP 3U +#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U +#define GRXSTS_PKTSTS_CH_HALTED 7U + +#define TEST_J 1U +#define TEST_K 2U +#define TEST_SE0_NAK 3U +#define TEST_PACKET 4U +#define TEST_FORCE_EN 5U + +#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_PCGCCTL_BASE) +#define USBx_HPRT0 *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_HOST_PORT_BASE) + +#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)(USBx_BASE + USB_OTG_DEVICE_BASE)) +#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)(USBx_BASE\ + + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) + +#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)(USBx_BASE\ + + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) + +#define USBx_DFIFO(i) *(__IO uint32_t *)(USBx_BASE + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) + +#define USBx_HOST ((USB_OTG_HostTypeDef *)(USBx_BASE + USB_OTG_HOST_BASE)) +#define USBx_HC(i) ((USB_OTG_HostChannelTypeDef *)(USBx_BASE\ + + USB_OTG_HOST_CHANNEL_BASE\ + + ((i) * USB_OTG_HOST_CHANNEL_SIZE))) + +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +#define EP_ADDR_MSK 0xFU + +#ifndef USE_USB_DOUBLE_BUFFER +#define USE_USB_DOUBLE_BUFFER 1U +#endif /* USE_USB_DOUBLE_BUFFER */ +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup USB_LL_Exported_Macros USB Low Layer Exported Macros + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +#define USB_MASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK &= ~(__INTERRUPT__)) +#define USB_UNMASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK |= (__INTERRUPT__)) + +#define CLEAR_IN_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_INEP(__EPNUM__)->DIEPINT = (__INTERRUPT__)) +#define CLEAR_OUT_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_OUTEP(__EPNUM__)->DOEPINT = (__INTERRUPT__)) +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup USB_LL_Exported_Functions USB Low Layer Exported Functions + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); +HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); +HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, uint32_t hclk, uint8_t speed); +HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode); +HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed); +HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num); +HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); +HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); +HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, + uint8_t ch_ep_num, uint16_t len, uint8_t dma); + +void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len); +HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_EPStopXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); +HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address); +HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup); +uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); +uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); +void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt); + +HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); +HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq); +HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state); +uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx); +uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, + uint8_t epnum, uint8_t dev_address, uint8_t speed, + uint8_t ep_type, uint16_t mps); +HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, + USB_OTG_HCTypeDef *hc, uint8_t dma); + +uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num); +HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num); +HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); +HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + + +#endif /* STM32F4xx_LL_USB_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h index 2b254a1..8b6cdfe 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h +++ b/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h @@ -1,307 +1,307 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_utils.h - * @author MCD Application Team - * @brief Header file of UTILS LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL UTILS driver contains a set of generic APIs that can be - used by user: - (+) Device electronic signature - (+) Timing functions - (+) PLL configuration functions - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_UTILS_H -#define __STM32F4xx_LL_UTILS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup UTILS_LL UTILS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Constants UTILS Private Constants - * @{ - */ - -/* Max delay can be used in LL_mDelay */ -#define LL_MAX_DELAY 0xFFFFFFFFU - -/** - * @brief Unique device ID register base address - */ -#define UID_BASE_ADDRESS UID_BASE - -/** - * @brief Flash size data register base address - */ -#define FLASHSIZE_BASE_ADDRESS FLASHSIZE_BASE - -/** - * @brief Package data register base address - */ -#define PACKAGE_BASE_ADDRESS PACKAGE_BASE - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Macros UTILS Private Macros - * @{ - */ -/** - * @} - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_ES_INIT UTILS Exported structures - * @{ - */ -/** - * @brief UTILS PLL structure definition - */ -typedef struct -{ - uint32_t PLLM; /*!< Division factor for PLL VCO input clock. - This parameter can be a value of @ref RCC_LL_EC_PLLM_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLN; /*!< Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = @ref RCC_PLLN_MIN_VALUE - and Max_Data = @ref RCC_PLLN_MIN_VALUE - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLP; /*!< Division for the main system clock. - This parameter can be a value of @ref RCC_LL_EC_PLLP_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ -} LL_UTILS_PLLInitTypeDef; - -/** - * @brief UTILS System, AHB and APB buses clock configuration structure definition - */ -typedef struct -{ - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_LL_EC_SYSCLK_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAHBPrescaler(). */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB1_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB1Prescaler(). */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB2_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB2Prescaler(). */ - -} LL_UTILS_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Constants UTILS Exported Constants - * @{ - */ - -/** @defgroup UTILS_EC_HSE_BYPASS HSE Bypass activation - * @{ - */ -#define LL_UTILS_HSEBYPASS_OFF 0x00000000U /*!< HSE Bypass is not enabled */ -#define LL_UTILS_HSEBYPASS_ON 0x00000001U /*!< HSE Bypass is enabled */ -/** - * @} - */ - -/** @defgroup UTILS_EC_PACKAGETYPE PACKAGE TYPE - * @{ - */ -#define LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 0x00000000U /*!< WLCSP36 or UFQFPN48 or LQFP64 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 0x00000100U /*!< WLCSP168 or FBGA169 or LQFP100 or LQFP64 or UFQFPN48 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 0x00000200U /*!< WLCSP64 or WLCSP81 or LQFP176 or UFBGA176 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 0x00000300U /*!< LQFP144 or UFBGA144 or UFBGA144 or UFBGA100 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 0x00000400U /*!< LQFP100 or LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 0x00000500U /*!< LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 0x00000700U /*!< TQFP64 or UFBGA144 or LQFP144 package type */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Functions UTILS Exported Functions - * @{ - */ - -/** @defgroup UTILS_EF_DEVICE_ELECTRONIC_SIGNATURE DEVICE ELECTRONIC SIGNATURE - * @{ - */ - -/** - * @brief Get Word0 of the unique device identifier (UID based on 96 bits) - * @retval UID[31:0] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word0(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)UID_BASE_ADDRESS))); -} - -/** - * @brief Get Word1 of the unique device identifier (UID based on 96 bits) - * @retval UID[63:32] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word1(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 4U)))); -} - -/** - * @brief Get Word2 of the unique device identifier (UID based on 96 bits) - * @retval UID[95:64] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word2(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 8U)))); -} - -/** - * @brief Get Flash memory size - * @note This bitfield indicates the size of the device Flash memory expressed in - * Kbytes. As an example, 0x040 corresponds to 64 Kbytes. - * @retval FLASH_SIZE[15:0]: Flash memory size - */ -__STATIC_INLINE uint32_t LL_GetFlashSize(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)FLASHSIZE_BASE_ADDRESS)) & 0xFFFF); -} - -/** - * @brief Get Package type - * @retval Returned value can be one of the following values: - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_GetPackageType(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)PACKAGE_BASE_ADDRESS)) & 0x0700U); -} - -/** - * @} - */ - -/** @defgroup UTILS_LL_EF_DELAY DELAY - * @{ - */ - -/** - * @brief This function configures the Cortex-M SysTick source of the time base. - * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) - * @note When a RTOS is used, it is recommended to avoid changing the SysTick - * configuration by calling this function, for a delay use rather osDelay RTOS service. - * @param Ticks Number of ticks - * @retval None - */ -__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks) -{ - /* Configure the SysTick to have interrupt in 1ms time base */ - SysTick->LOAD = (uint32_t)((HCLKFrequency / Ticks) - 1UL); /* set reload register */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable the Systick Timer */ -} - -void LL_Init1msTick(uint32_t HCLKFrequency); -void LL_mDelay(uint32_t Delay); - -/** - * @} - */ - -/** @defgroup UTILS_EF_SYSTEM SYSTEM - * @{ - */ - -void LL_SetSystemCoreClock(uint32_t HCLKFrequency); -ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency); -ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, - LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); -ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, - LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_UTILS_H */ +/** + ****************************************************************************** + * @file stm32f4xx_ll_utils.h + * @author MCD Application Team + * @brief Header file of UTILS LL module. + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The LL UTILS driver contains a set of generic APIs that can be + used by user: + (+) Device electronic signature + (+) Timing functions + (+) PLL configuration functions + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_LL_UTILS_H +#define __STM32F4xx_LL_UTILS_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +/** @defgroup UTILS_LL UTILS + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup UTILS_LL_Private_Constants UTILS Private Constants + * @{ + */ + +/* Max delay can be used in LL_mDelay */ +#define LL_MAX_DELAY 0xFFFFFFFFU + +/** + * @brief Unique device ID register base address + */ +#define UID_BASE_ADDRESS UID_BASE + +/** + * @brief Flash size data register base address + */ +#define FLASHSIZE_BASE_ADDRESS FLASHSIZE_BASE + +/** + * @brief Package data register base address + */ +#define PACKAGE_BASE_ADDRESS PACKAGE_BASE + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup UTILS_LL_Private_Macros UTILS Private Macros + * @{ + */ +/** + * @} + */ +/* Exported types ------------------------------------------------------------*/ +/** @defgroup UTILS_LL_ES_INIT UTILS Exported structures + * @{ + */ +/** + * @brief UTILS PLL structure definition + */ +typedef struct +{ + uint32_t PLLM; /*!< Division factor for PLL VCO input clock. + This parameter can be a value of @ref RCC_LL_EC_PLLM_DIV + + This feature can be modified afterwards using unitary function + @ref LL_RCC_PLL_ConfigDomain_SYS(). */ + + uint32_t PLLN; /*!< Multiplication factor for PLL VCO output clock. + This parameter must be a number between Min_Data = @ref RCC_PLLN_MIN_VALUE + and Max_Data = @ref RCC_PLLN_MIN_VALUE + + This feature can be modified afterwards using unitary function + @ref LL_RCC_PLL_ConfigDomain_SYS(). */ + + uint32_t PLLP; /*!< Division for the main system clock. + This parameter can be a value of @ref RCC_LL_EC_PLLP_DIV + + This feature can be modified afterwards using unitary function + @ref LL_RCC_PLL_ConfigDomain_SYS(). */ +} LL_UTILS_PLLInitTypeDef; + +/** + * @brief UTILS System, AHB and APB buses clock configuration structure definition + */ +typedef struct +{ + uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). + This parameter can be a value of @ref RCC_LL_EC_SYSCLK_DIV + + This feature can be modified afterwards using unitary function + @ref LL_RCC_SetAHBPrescaler(). */ + + uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). + This parameter can be a value of @ref RCC_LL_EC_APB1_DIV + + This feature can be modified afterwards using unitary function + @ref LL_RCC_SetAPB1Prescaler(). */ + + uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). + This parameter can be a value of @ref RCC_LL_EC_APB2_DIV + + This feature can be modified afterwards using unitary function + @ref LL_RCC_SetAPB2Prescaler(). */ + +} LL_UTILS_ClkInitTypeDef; + +/** + * @} + */ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup UTILS_LL_Exported_Constants UTILS Exported Constants + * @{ + */ + +/** @defgroup UTILS_EC_HSE_BYPASS HSE Bypass activation + * @{ + */ +#define LL_UTILS_HSEBYPASS_OFF 0x00000000U /*!< HSE Bypass is not enabled */ +#define LL_UTILS_HSEBYPASS_ON 0x00000001U /*!< HSE Bypass is enabled */ +/** + * @} + */ + +/** @defgroup UTILS_EC_PACKAGETYPE PACKAGE TYPE + * @{ + */ +#define LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 0x00000000U /*!< WLCSP36 or UFQFPN48 or LQFP64 package type */ +#define LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 0x00000100U /*!< WLCSP168 or FBGA169 or LQFP100 or LQFP64 or UFQFPN48 package type */ +#define LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 0x00000200U /*!< WLCSP64 or WLCSP81 or LQFP176 or UFBGA176 package type */ +#define LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 0x00000300U /*!< LQFP144 or UFBGA144 or UFBGA144 or UFBGA100 package type */ +#define LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 0x00000400U /*!< LQFP100 or LQFP208 or TFBGA216 package type */ +#define LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 0x00000500U /*!< LQFP208 or TFBGA216 package type */ +#define LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 0x00000700U /*!< TQFP64 or UFBGA144 or LQFP144 package type */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup UTILS_LL_Exported_Functions UTILS Exported Functions + * @{ + */ + +/** @defgroup UTILS_EF_DEVICE_ELECTRONIC_SIGNATURE DEVICE ELECTRONIC SIGNATURE + * @{ + */ + +/** + * @brief Get Word0 of the unique device identifier (UID based on 96 bits) + * @retval UID[31:0] + */ +__STATIC_INLINE uint32_t LL_GetUID_Word0(void) +{ + return (uint32_t)(READ_REG(*((uint32_t *)UID_BASE_ADDRESS))); +} + +/** + * @brief Get Word1 of the unique device identifier (UID based on 96 bits) + * @retval UID[63:32] + */ +__STATIC_INLINE uint32_t LL_GetUID_Word1(void) +{ + return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 4U)))); +} + +/** + * @brief Get Word2 of the unique device identifier (UID based on 96 bits) + * @retval UID[95:64] + */ +__STATIC_INLINE uint32_t LL_GetUID_Word2(void) +{ + return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 8U)))); +} + +/** + * @brief Get Flash memory size + * @note This bitfield indicates the size of the device Flash memory expressed in + * Kbytes. As an example, 0x040 corresponds to 64 Kbytes. + * @retval FLASH_SIZE[15:0]: Flash memory size + */ +__STATIC_INLINE uint32_t LL_GetFlashSize(void) +{ + return (uint32_t)(READ_REG(*((uint32_t *)FLASHSIZE_BASE_ADDRESS)) & 0xFFFF); +} + +/** + * @brief Get Package type + * @retval Returned value can be one of the following values: + * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 (*) + * @arg @ref LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 (*) + * + * (*) value not defined in all devices. + */ +__STATIC_INLINE uint32_t LL_GetPackageType(void) +{ + return (uint32_t)(READ_REG(*((uint32_t *)PACKAGE_BASE_ADDRESS)) & 0x0700U); +} + +/** + * @} + */ + +/** @defgroup UTILS_LL_EF_DELAY DELAY + * @{ + */ + +/** + * @brief This function configures the Cortex-M SysTick source of the time base. + * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) + * @note When a RTOS is used, it is recommended to avoid changing the SysTick + * configuration by calling this function, for a delay use rather osDelay RTOS service. + * @param Ticks Number of ticks + * @retval None + */ +__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks) +{ + /* Configure the SysTick to have interrupt in 1ms time base */ + SysTick->LOAD = (uint32_t)((HCLKFrequency / Ticks) - 1UL); /* set reload register */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable the Systick Timer */ +} + +void LL_Init1msTick(uint32_t HCLKFrequency); +void LL_mDelay(uint32_t Delay); + +/** + * @} + */ + +/** @defgroup UTILS_EF_SYSTEM SYSTEM + * @{ + */ + +void LL_SetSystemCoreClock(uint32_t HCLKFrequency); +ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency); +ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, + LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); +ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, + LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_LL_UTILS_H */ diff --git a/Drivers/STM32F4xx_HAL_Driver/LICENSE.txt b/Drivers/STM32F4xx_HAL_Driver/LICENSE.txt index 3edc4d1..b40364c 100644 --- a/Drivers/STM32F4xx_HAL_Driver/LICENSE.txt +++ b/Drivers/STM32F4xx_HAL_Driver/LICENSE.txt @@ -1,6 +1,6 @@ -This software component is provided to you as part of a software package and -applicable license terms are in the Package_license file. If you received this -software component outside of a package or without applicable license terms, -the terms of the BSD-3-Clause license shall apply. -You may obtain a copy of the BSD-3-Clause at: -https://opensource.org/licenses/BSD-3-Clause +This software component is provided to you as part of a software package and +applicable license terms are in the Package_license file. If you received this +software component outside of a package or without applicable license terms, +the terms of the BSD-3-Clause license shall apply. +You may obtain a copy of the BSD-3-Clause at: +https://opensource.org/licenses/BSD-3-Clause diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c index 9ba2ba7..9977a70 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c @@ -1,615 +1,615 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal.c - * @author MCD Application Team - * @brief HAL module driver. - * This is the common part of the HAL initialization - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The common HAL driver contains a set of generic and common APIs that can be - used by the PPP peripheral drivers and the user to start using the HAL. - [..] - The HAL contains two APIs' categories: - (+) Common HAL APIs - (+) Services HAL APIs - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup HAL HAL - * @brief HAL module driver. - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup HAL_Private_Constants - * @{ - */ -/** - * @brief STM32F4xx HAL Driver version number V1.8.1 - */ -#define __STM32F4xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */ -#define __STM32F4xx_HAL_VERSION_SUB1 (0x08U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_HAL_VERSION_SUB2 (0x01U) /*!< [15:8] sub2 version */ -#define __STM32F4xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_HAL_VERSION ((__STM32F4xx_HAL_VERSION_MAIN << 24U)\ - |(__STM32F4xx_HAL_VERSION_SUB1 << 16U)\ - |(__STM32F4xx_HAL_VERSION_SUB2 << 8U )\ - |(__STM32F4xx_HAL_VERSION_RC)) - -#define IDCODE_DEVID_MASK 0x00000FFFU - -/* ------------ RCC registers bit address in the alias region ----------- */ -#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) -/* --- MEMRMP Register ---*/ -/* Alias word address of UFB_MODE bit */ -#define MEMRMP_OFFSET SYSCFG_OFFSET -#define UFB_MODE_BIT_NUMBER SYSCFG_MEMRMP_UFB_MODE_Pos -#define UFB_MODE_BB (uint32_t)(PERIPH_BB_BASE + (MEMRMP_OFFSET * 32U) + (UFB_MODE_BIT_NUMBER * 4U)) - -/* --- CMPCR Register ---*/ -/* Alias word address of CMP_PD bit */ -#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20U) -#define CMP_PD_BIT_NUMBER SYSCFG_CMPCR_CMP_PD_Pos -#define CMPCR_CMP_PD_BB (uint32_t)(PERIPH_BB_BASE + (CMPCR_OFFSET * 32U) + (CMP_PD_BIT_NUMBER * 4U)) - -/* --- MCHDLYCR Register ---*/ -/* Alias word address of BSCKSEL bit */ -#define MCHDLYCR_OFFSET (SYSCFG_OFFSET + 0x30U) -#define BSCKSEL_BIT_NUMBER SYSCFG_MCHDLYCR_BSCKSEL_Pos -#define MCHDLYCR_BSCKSEL_BB (uint32_t)(PERIPH_BB_BASE + (MCHDLYCR_OFFSET * 32U) + (BSCKSEL_BIT_NUMBER * 4U)) -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup HAL_Private_Variables - * @{ - */ -__IO uint32_t uwTick; -uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */ -HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT; /* 1KHz */ -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup HAL_Exported_Functions HAL Exported Functions - * @{ - */ - -/** @defgroup HAL_Exported_Functions_Group1 Initialization and de-initialization Functions - * @brief Initialization and de-initialization functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initializes the Flash interface the NVIC allocation and initial clock - configuration. It initializes the systick also when timeout is needed - and the backup domain when enabled. - (+) De-Initializes common part of the HAL. - (+) Configure the time base source to have 1ms time base with a dedicated - Tick interrupt priority. - (++) SysTick timer is used by default as source of time base, but user - can eventually implement his proper time base source (a general purpose - timer for example or other time source), keeping in mind that Time base - duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and - handled in milliseconds basis. - (++) Time base configuration function (HAL_InitTick ()) is called automatically - at the beginning of the program after reset by HAL_Init() or at any time - when clock is configured, by HAL_RCC_ClockConfig(). - (++) Source of time base is configured to generate interrupts at regular - time intervals. Care must be taken if HAL_Delay() is called from a - peripheral ISR process, the Tick interrupt line must have higher priority - (numerically lower) than the peripheral interrupt. Otherwise the caller - ISR process will be blocked. - (++) functions affecting time base configurations are declared as __weak - to make override possible in case of other implementations in user file. -@endverbatim - * @{ - */ - -/** - * @brief This function is used to initialize the HAL Library; it must be the first - * instruction to be executed in the main program (before to call any other - * HAL function), it performs the following: - * Configure the Flash prefetch, instruction and Data caches. - * Configures the SysTick to generate an interrupt each 1 millisecond, - * which is clocked by the HSI (at this stage, the clock is not yet - * configured and thus the system is running from the internal HSI at 16 MHz). - * Set NVIC Group Priority to 4. - * Calls the HAL_MspInit() callback function defined in user file - * "stm32f4xx_hal_msp.c" to do the global low level hardware initialization - * - * @note SysTick is used as time base for the HAL_Delay() function, the application - * need to ensure that the SysTick time base is always set to 1 millisecond - * to have correct HAL operation. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_Init(void) -{ - /* Configure Flash prefetch, Instruction cache, Data cache */ -#if (INSTRUCTION_CACHE_ENABLE != 0U) - __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); -#endif /* INSTRUCTION_CACHE_ENABLE */ - -#if (DATA_CACHE_ENABLE != 0U) - __HAL_FLASH_DATA_CACHE_ENABLE(); -#endif /* DATA_CACHE_ENABLE */ - -#if (PREFETCH_ENABLE != 0U) - __HAL_FLASH_PREFETCH_BUFFER_ENABLE(); -#endif /* PREFETCH_ENABLE */ - - /* Set Interrupt Group Priority */ - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - - /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ - HAL_InitTick(TICK_INT_PRIORITY); - - /* Init the low level hardware */ - HAL_MspInit(); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief This function de-Initializes common part of the HAL and stops the systick. - * This function is optional. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DeInit(void) -{ - /* Reset of all peripherals */ - __HAL_RCC_APB1_FORCE_RESET(); - __HAL_RCC_APB1_RELEASE_RESET(); - - __HAL_RCC_APB2_FORCE_RESET(); - __HAL_RCC_APB2_RELEASE_RESET(); - - __HAL_RCC_AHB1_FORCE_RESET(); - __HAL_RCC_AHB1_RELEASE_RESET(); - - __HAL_RCC_AHB2_FORCE_RESET(); - __HAL_RCC_AHB2_RELEASE_RESET(); - - __HAL_RCC_AHB3_FORCE_RESET(); - __HAL_RCC_AHB3_RELEASE_RESET(); - - /* De-Init the low level hardware */ - HAL_MspDeInit(); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initialize the MSP. - * @retval None - */ -__weak void HAL_MspInit(void) -{ - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the MSP. - * @retval None - */ -__weak void HAL_MspDeInit(void) -{ - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief This function configures the source of the time base. - * The time source is configured to have 1ms time base with a dedicated - * Tick interrupt priority. - * @note This function is called automatically at the beginning of program after - * reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig(). - * @note In the default implementation, SysTick timer is the source of time base. - * It is used to generate interrupts at regular time intervals. - * Care must be taken if HAL_Delay() is called from a peripheral ISR process, - * The SysTick interrupt must have higher priority (numerically lower) - * than the peripheral interrupt. Otherwise the caller ISR process will be blocked. - * The function is declared as __weak to be overwritten in case of other - * implementation in user file. - * @param TickPriority Tick interrupt priority. - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) -{ - /* Configure the SysTick to have interrupt in 1ms time basis*/ - if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) - { - return HAL_ERROR; - } - - /* Configure the SysTick IRQ priority */ - if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - { - HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); - uwTickPrio = TickPriority; - } - else - { - return HAL_ERROR; - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup HAL_Exported_Functions_Group2 HAL Control functions - * @brief HAL Control functions - * -@verbatim - =============================================================================== - ##### HAL Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Provide a tick value in millisecond - (+) Provide a blocking delay in millisecond - (+) Suspend the time base source interrupt - (+) Resume the time base source interrupt - (+) Get the HAL API driver version - (+) Get the device identifier - (+) Get the device revision identifier - (+) Enable/Disable Debug module during SLEEP mode - (+) Enable/Disable Debug module during STOP mode - (+) Enable/Disable Debug module during STANDBY mode - -@endverbatim - * @{ - */ - -/** - * @brief This function is called to increment a global variable "uwTick" - * used as application time base. - * @note In the default implementation, this variable is incremented each 1ms - * in SysTick ISR. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_IncTick(void) -{ - uwTick += uwTickFreq; -} - -/** - * @brief Provides a tick value in millisecond. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval tick value - */ -__weak uint32_t HAL_GetTick(void) -{ - return uwTick; -} - -/** - * @brief This function returns a tick priority. - * @retval tick priority - */ -uint32_t HAL_GetTickPrio(void) -{ - return uwTickPrio; -} - -/** - * @brief Set new tick Freq. - * @retval Status - */ -HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_TickFreqTypeDef prevTickFreq; - - assert_param(IS_TICKFREQ(Freq)); - - if (uwTickFreq != Freq) - { - /* Back up uwTickFreq frequency */ - prevTickFreq = uwTickFreq; - - /* Update uwTickFreq global variable used by HAL_InitTick() */ - uwTickFreq = Freq; - - /* Apply the new tick Freq */ - status = HAL_InitTick(uwTickPrio); - - if (status != HAL_OK) - { - /* Restore previous tick frequency */ - uwTickFreq = prevTickFreq; - } - } - - return status; -} - -/** - * @brief Return tick frequency. - * @retval tick period in Hz - */ -HAL_TickFreqTypeDef HAL_GetTickFreq(void) -{ - return uwTickFreq; -} - -/** - * @brief This function provides minimum delay (in milliseconds) based - * on variable incremented. - * @note In the default implementation , SysTick timer is the source of time base. - * It is used to generate interrupts at regular time intervals where uwTick - * is incremented. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @param Delay specifies the delay time length, in milliseconds. - * @retval None - */ -__weak void HAL_Delay(uint32_t Delay) -{ - uint32_t tickstart = HAL_GetTick(); - uint32_t wait = Delay; - - /* Add a freq to guarantee minimum wait */ - if (wait < HAL_MAX_DELAY) - { - wait += (uint32_t)(uwTickFreq); - } - - while((HAL_GetTick() - tickstart) < wait) - { - } -} - -/** - * @brief Suspend Tick increment. - * @note In the default implementation , SysTick timer is the source of time base. It is - * used to generate interrupts at regular time intervals. Once HAL_SuspendTick() - * is called, the SysTick interrupt will be disabled and so Tick increment - * is suspended. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_SuspendTick(void) -{ - /* Disable SysTick Interrupt */ - SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk; -} - -/** - * @brief Resume Tick increment. - * @note In the default implementation , SysTick timer is the source of time base. It is - * used to generate interrupts at regular time intervals. Once HAL_ResumeTick() - * is called, the SysTick interrupt will be enabled and so Tick increment - * is resumed. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_ResumeTick(void) -{ - /* Enable SysTick Interrupt */ - SysTick->CTRL |= SysTick_CTRL_TICKINT_Msk; -} - -/** - * @brief Returns the HAL revision - * @retval version : 0xXYZR (8bits for each decimal, R for RC) - */ -uint32_t HAL_GetHalVersion(void) -{ - return __STM32F4xx_HAL_VERSION; -} - -/** - * @brief Returns the device revision identifier. - * @retval Device revision identifier - */ -uint32_t HAL_GetREVID(void) -{ - return((DBGMCU->IDCODE) >> 16U); -} - -/** - * @brief Returns the device identifier. - * @retval Device identifier - */ -uint32_t HAL_GetDEVID(void) -{ - return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK); -} - -/** - * @brief Enable the Debug Module during SLEEP mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGSleepMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Disable the Debug Module during SLEEP mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGSleepMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Enable the Debug Module during STOP mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGStopMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Disable the Debug Module during STOP mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGStopMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Enable the Debug Module during STANDBY mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGStandbyMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Disable the Debug Module during STANDBY mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGStandbyMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Enables the I/O Compensation Cell. - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V. - * @retval None - */ -void HAL_EnableCompensationCell(void) -{ - *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)ENABLE; -} - -/** - * @brief Power-down the I/O Compensation Cell. - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V. - * @retval None - */ -void HAL_DisableCompensationCell(void) -{ - *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)DISABLE; -} - -/** - * @brief Returns first word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw0(void) -{ - return (READ_REG(*((uint32_t *)UID_BASE))); -} - -/** - * @brief Returns second word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw1(void) -{ - return (READ_REG(*((uint32_t *)(UID_BASE + 4U)))); -} - -/** - * @brief Returns third word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw2(void) -{ - return (READ_REG(*((uint32_t *)(UID_BASE + 8U)))); -} - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enables the Internal FLASH Bank Swapping. - * - * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. - * - * @note Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000) - * and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000) - * - * @retval None - */ -void HAL_EnableMemorySwappingBank(void) -{ - *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Internal FLASH Bank Swapping. - * - * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. - * - * @note The default state : Flash Bank1 mapped at 0x08000000 (and aliased @0x00000000) - * and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000) - * - * @retval None - */ -void HAL_DisableMemorySwappingBank(void) -{ - *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)DISABLE; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - - +/** + ****************************************************************************** + * @file stm32f4xx_hal.c + * @author MCD Application Team + * @brief HAL module driver. + * This is the common part of the HAL initialization + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The common HAL driver contains a set of generic and common APIs that can be + used by the PPP peripheral drivers and the user to start using the HAL. + [..] + The HAL contains two APIs' categories: + (+) Common HAL APIs + (+) Services HAL APIs + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup HAL HAL + * @brief HAL module driver. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup HAL_Private_Constants + * @{ + */ +/** + * @brief STM32F4xx HAL Driver version number V1.8.1 + */ +#define __STM32F4xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */ +#define __STM32F4xx_HAL_VERSION_SUB1 (0x08U) /*!< [23:16] sub1 version */ +#define __STM32F4xx_HAL_VERSION_SUB2 (0x01U) /*!< [15:8] sub2 version */ +#define __STM32F4xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */ +#define __STM32F4xx_HAL_VERSION ((__STM32F4xx_HAL_VERSION_MAIN << 24U)\ + |(__STM32F4xx_HAL_VERSION_SUB1 << 16U)\ + |(__STM32F4xx_HAL_VERSION_SUB2 << 8U )\ + |(__STM32F4xx_HAL_VERSION_RC)) + +#define IDCODE_DEVID_MASK 0x00000FFFU + +/* ------------ RCC registers bit address in the alias region ----------- */ +#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) +/* --- MEMRMP Register ---*/ +/* Alias word address of UFB_MODE bit */ +#define MEMRMP_OFFSET SYSCFG_OFFSET +#define UFB_MODE_BIT_NUMBER SYSCFG_MEMRMP_UFB_MODE_Pos +#define UFB_MODE_BB (uint32_t)(PERIPH_BB_BASE + (MEMRMP_OFFSET * 32U) + (UFB_MODE_BIT_NUMBER * 4U)) + +/* --- CMPCR Register ---*/ +/* Alias word address of CMP_PD bit */ +#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20U) +#define CMP_PD_BIT_NUMBER SYSCFG_CMPCR_CMP_PD_Pos +#define CMPCR_CMP_PD_BB (uint32_t)(PERIPH_BB_BASE + (CMPCR_OFFSET * 32U) + (CMP_PD_BIT_NUMBER * 4U)) + +/* --- MCHDLYCR Register ---*/ +/* Alias word address of BSCKSEL bit */ +#define MCHDLYCR_OFFSET (SYSCFG_OFFSET + 0x30U) +#define BSCKSEL_BIT_NUMBER SYSCFG_MCHDLYCR_BSCKSEL_Pos +#define MCHDLYCR_BSCKSEL_BB (uint32_t)(PERIPH_BB_BASE + (MCHDLYCR_OFFSET * 32U) + (BSCKSEL_BIT_NUMBER * 4U)) +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup HAL_Private_Variables + * @{ + */ +__IO uint32_t uwTick; +uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */ +HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT; /* 1KHz */ +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HAL_Exported_Functions HAL Exported Functions + * @{ + */ + +/** @defgroup HAL_Exported_Functions_Group1 Initialization and de-initialization Functions + * @brief Initialization and de-initialization functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initializes the Flash interface the NVIC allocation and initial clock + configuration. It initializes the systick also when timeout is needed + and the backup domain when enabled. + (+) De-Initializes common part of the HAL. + (+) Configure the time base source to have 1ms time base with a dedicated + Tick interrupt priority. + (++) SysTick timer is used by default as source of time base, but user + can eventually implement his proper time base source (a general purpose + timer for example or other time source), keeping in mind that Time base + duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and + handled in milliseconds basis. + (++) Time base configuration function (HAL_InitTick ()) is called automatically + at the beginning of the program after reset by HAL_Init() or at any time + when clock is configured, by HAL_RCC_ClockConfig(). + (++) Source of time base is configured to generate interrupts at regular + time intervals. Care must be taken if HAL_Delay() is called from a + peripheral ISR process, the Tick interrupt line must have higher priority + (numerically lower) than the peripheral interrupt. Otherwise the caller + ISR process will be blocked. + (++) functions affecting time base configurations are declared as __weak + to make override possible in case of other implementations in user file. +@endverbatim + * @{ + */ + +/** + * @brief This function is used to initialize the HAL Library; it must be the first + * instruction to be executed in the main program (before to call any other + * HAL function), it performs the following: + * Configure the Flash prefetch, instruction and Data caches. + * Configures the SysTick to generate an interrupt each 1 millisecond, + * which is clocked by the HSI (at this stage, the clock is not yet + * configured and thus the system is running from the internal HSI at 16 MHz). + * Set NVIC Group Priority to 4. + * Calls the HAL_MspInit() callback function defined in user file + * "stm32f4xx_hal_msp.c" to do the global low level hardware initialization + * + * @note SysTick is used as time base for the HAL_Delay() function, the application + * need to ensure that the SysTick time base is always set to 1 millisecond + * to have correct HAL operation. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_Init(void) +{ + /* Configure Flash prefetch, Instruction cache, Data cache */ +#if (INSTRUCTION_CACHE_ENABLE != 0U) + __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); +#endif /* INSTRUCTION_CACHE_ENABLE */ + +#if (DATA_CACHE_ENABLE != 0U) + __HAL_FLASH_DATA_CACHE_ENABLE(); +#endif /* DATA_CACHE_ENABLE */ + +#if (PREFETCH_ENABLE != 0U) + __HAL_FLASH_PREFETCH_BUFFER_ENABLE(); +#endif /* PREFETCH_ENABLE */ + + /* Set Interrupt Group Priority */ + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + + /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ + HAL_InitTick(TICK_INT_PRIORITY); + + /* Init the low level hardware */ + HAL_MspInit(); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief This function de-Initializes common part of the HAL and stops the systick. + * This function is optional. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DeInit(void) +{ + /* Reset of all peripherals */ + __HAL_RCC_APB1_FORCE_RESET(); + __HAL_RCC_APB1_RELEASE_RESET(); + + __HAL_RCC_APB2_FORCE_RESET(); + __HAL_RCC_APB2_RELEASE_RESET(); + + __HAL_RCC_AHB1_FORCE_RESET(); + __HAL_RCC_AHB1_RELEASE_RESET(); + + __HAL_RCC_AHB2_FORCE_RESET(); + __HAL_RCC_AHB2_RELEASE_RESET(); + + __HAL_RCC_AHB3_FORCE_RESET(); + __HAL_RCC_AHB3_RELEASE_RESET(); + + /* De-Init the low level hardware */ + HAL_MspDeInit(); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initialize the MSP. + * @retval None + */ +__weak void HAL_MspInit(void) +{ + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the MSP. + * @retval None + */ +__weak void HAL_MspDeInit(void) +{ + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief This function configures the source of the time base. + * The time source is configured to have 1ms time base with a dedicated + * Tick interrupt priority. + * @note This function is called automatically at the beginning of program after + * reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig(). + * @note In the default implementation, SysTick timer is the source of time base. + * It is used to generate interrupts at regular time intervals. + * Care must be taken if HAL_Delay() is called from a peripheral ISR process, + * The SysTick interrupt must have higher priority (numerically lower) + * than the peripheral interrupt. Otherwise the caller ISR process will be blocked. + * The function is declared as __weak to be overwritten in case of other + * implementation in user file. + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) +{ + /* Configure the SysTick to have interrupt in 1ms time basis*/ + if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) + { + return HAL_ERROR; + } + + /* Configure the SysTick IRQ priority */ + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + { + HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); + uwTickPrio = TickPriority; + } + else + { + return HAL_ERROR; + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup HAL_Exported_Functions_Group2 HAL Control functions + * @brief HAL Control functions + * +@verbatim + =============================================================================== + ##### HAL Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Provide a tick value in millisecond + (+) Provide a blocking delay in millisecond + (+) Suspend the time base source interrupt + (+) Resume the time base source interrupt + (+) Get the HAL API driver version + (+) Get the device identifier + (+) Get the device revision identifier + (+) Enable/Disable Debug module during SLEEP mode + (+) Enable/Disable Debug module during STOP mode + (+) Enable/Disable Debug module during STANDBY mode + +@endverbatim + * @{ + */ + +/** + * @brief This function is called to increment a global variable "uwTick" + * used as application time base. + * @note In the default implementation, this variable is incremented each 1ms + * in SysTick ISR. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_IncTick(void) +{ + uwTick += uwTickFreq; +} + +/** + * @brief Provides a tick value in millisecond. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval tick value + */ +__weak uint32_t HAL_GetTick(void) +{ + return uwTick; +} + +/** + * @brief This function returns a tick priority. + * @retval tick priority + */ +uint32_t HAL_GetTickPrio(void) +{ + return uwTickPrio; +} + +/** + * @brief Set new tick Freq. + * @retval Status + */ +HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_TickFreqTypeDef prevTickFreq; + + assert_param(IS_TICKFREQ(Freq)); + + if (uwTickFreq != Freq) + { + /* Back up uwTickFreq frequency */ + prevTickFreq = uwTickFreq; + + /* Update uwTickFreq global variable used by HAL_InitTick() */ + uwTickFreq = Freq; + + /* Apply the new tick Freq */ + status = HAL_InitTick(uwTickPrio); + + if (status != HAL_OK) + { + /* Restore previous tick frequency */ + uwTickFreq = prevTickFreq; + } + } + + return status; +} + +/** + * @brief Return tick frequency. + * @retval tick period in Hz + */ +HAL_TickFreqTypeDef HAL_GetTickFreq(void) +{ + return uwTickFreq; +} + +/** + * @brief This function provides minimum delay (in milliseconds) based + * on variable incremented. + * @note In the default implementation , SysTick timer is the source of time base. + * It is used to generate interrupts at regular time intervals where uwTick + * is incremented. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @param Delay specifies the delay time length, in milliseconds. + * @retval None + */ +__weak void HAL_Delay(uint32_t Delay) +{ + uint32_t tickstart = HAL_GetTick(); + uint32_t wait = Delay; + + /* Add a freq to guarantee minimum wait */ + if (wait < HAL_MAX_DELAY) + { + wait += (uint32_t)(uwTickFreq); + } + + while((HAL_GetTick() - tickstart) < wait) + { + } +} + +/** + * @brief Suspend Tick increment. + * @note In the default implementation , SysTick timer is the source of time base. It is + * used to generate interrupts at regular time intervals. Once HAL_SuspendTick() + * is called, the SysTick interrupt will be disabled and so Tick increment + * is suspended. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_SuspendTick(void) +{ + /* Disable SysTick Interrupt */ + SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk; +} + +/** + * @brief Resume Tick increment. + * @note In the default implementation , SysTick timer is the source of time base. It is + * used to generate interrupts at regular time intervals. Once HAL_ResumeTick() + * is called, the SysTick interrupt will be enabled and so Tick increment + * is resumed. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_ResumeTick(void) +{ + /* Enable SysTick Interrupt */ + SysTick->CTRL |= SysTick_CTRL_TICKINT_Msk; +} + +/** + * @brief Returns the HAL revision + * @retval version : 0xXYZR (8bits for each decimal, R for RC) + */ +uint32_t HAL_GetHalVersion(void) +{ + return __STM32F4xx_HAL_VERSION; +} + +/** + * @brief Returns the device revision identifier. + * @retval Device revision identifier + */ +uint32_t HAL_GetREVID(void) +{ + return((DBGMCU->IDCODE) >> 16U); +} + +/** + * @brief Returns the device identifier. + * @retval Device identifier + */ +uint32_t HAL_GetDEVID(void) +{ + return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK); +} + +/** + * @brief Enable the Debug Module during SLEEP mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGSleepMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Disable the Debug Module during SLEEP mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGSleepMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Enable the Debug Module during STOP mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGStopMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Disable the Debug Module during STOP mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGStopMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Enable the Debug Module during STANDBY mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGStandbyMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Disable the Debug Module during STANDBY mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGStandbyMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Enables the I/O Compensation Cell. + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V. + * @retval None + */ +void HAL_EnableCompensationCell(void) +{ + *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)ENABLE; +} + +/** + * @brief Power-down the I/O Compensation Cell. + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V. + * @retval None + */ +void HAL_DisableCompensationCell(void) +{ + *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)DISABLE; +} + +/** + * @brief Returns first word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw0(void) +{ + return (READ_REG(*((uint32_t *)UID_BASE))); +} + +/** + * @brief Returns second word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw1(void) +{ + return (READ_REG(*((uint32_t *)(UID_BASE + 4U)))); +} + +/** + * @brief Returns third word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw2(void) +{ + return (READ_REG(*((uint32_t *)(UID_BASE + 8U)))); +} + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Enables the Internal FLASH Bank Swapping. + * + * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. + * + * @note Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000) + * and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000) + * + * @retval None + */ +void HAL_EnableMemorySwappingBank(void) +{ + *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Internal FLASH Bank Swapping. + * + * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. + * + * @note The default state : Flash Bank1 mapped at 0x08000000 (and aliased @0x00000000) + * and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000) + * + * @retval None + */ +void HAL_DisableMemorySwappingBank(void) +{ + *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)DISABLE; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c new file mode 100644 index 0000000..bf98a2b --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c @@ -0,0 +1,2110 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the Analog to Digital Converter (ADC) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + Peripheral State functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### ADC Peripheral features ##### + ============================================================================== + [..] + (#) 12-bit, 10-bit, 8-bit or 6-bit configurable resolution. + (#) Interrupt generation at the end of conversion, end of injected conversion, + and in case of analog watchdog or overrun events + (#) Single and continuous conversion modes. + (#) Scan mode for automatic conversion of channel 0 to channel x. + (#) Data alignment with in-built data coherency. + (#) Channel-wise programmable sampling time. + (#) External trigger option with configurable polarity for both regular and + injected conversion. + (#) Dual/Triple mode (on devices with 2 ADCs or more). + (#) Configurable DMA data storage in Dual/Triple ADC mode. + (#) Configurable delay between conversions in Dual/Triple interleaved mode. + (#) ADC conversion type (refer to the datasheets). + (#) ADC supply requirements: 2.4 V to 3.6 V at full speed and down to 1.8 V at + slower speed. + (#) ADC input range: VREF(minus) = VIN = VREF(plus). + (#) DMA request generation during regular channel conversion. + + + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): + (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() + (##) ADC pins configuration + (+++) Enable the clock for the ADC GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE() + (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() + (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) + (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() + (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() + (+++) Configure and enable two DMA streams stream for managing data + transfer from peripheral to memory (output stream) + (+++) Associate the initialized DMA handle to the CRYP DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the two DMA Streams. The output stream should have higher + priority than the input stream. + + *** Configuration of ADC, groups regular/injected, channels parameters *** + ============================================================================== + [..] + (#) Configure the ADC parameters (resolution, data alignment, ...) + and regular group parameters (conversion trigger, sequencer, ...) + using function HAL_ADC_Init(). + + (#) Configure the channels for regular group parameters (channel number, + channel rank into sequencer, ..., into regular group) + using function HAL_ADC_ConfigChannel(). + + (#) Optionally, configure the injected group parameters (conversion trigger, + sequencer, ..., of injected group) + and the channels for injected group parameters (channel number, + channel rank into sequencer, ..., into injected group) + using function HAL_ADCEx_InjectedConfigChannel(). + + (#) Optionally, configure the analog watchdog parameters (channels + monitored, thresholds, ...) using function HAL_ADC_AnalogWDGConfig(). + + (#) Optionally, for devices with several ADC instances: configure the + multimode parameters using function HAL_ADCEx_MultiModeConfigChannel(). + + *** Execution of ADC conversions *** + ============================================================================== + [..] + (#) ADC driver can be used among three modes: polling, interruption, + transfer by DMA. + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the ADC peripheral using HAL_ADC_Start() + (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage + user can specify the value of timeout according to his end application + (+) To read the ADC converted values, use the HAL_ADC_GetValue() function. + (+) Stop the ADC peripheral using HAL_ADC_Stop() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Start the ADC peripheral using HAL_ADC_Start_IT() + (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine + (+) At ADC end of conversion HAL_ADC_ConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ConvCpltCallback + (+) In case of ADC Error, HAL_ADC_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ErrorCallback + (+) Stop the ADC peripheral using HAL_ADC_Stop_IT() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Start the ADC peripheral using HAL_ADC_Start_DMA(), at this stage the user specify the length + of data to be transferred at each end of conversion + (+) At The end of data transfer by HAL_ADC_ConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ConvCpltCallback + (+) In case of transfer Error, HAL_ADC_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ErrorCallback + (+) Stop the ADC peripheral using HAL_ADC_Stop_DMA() + + *** ADC HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in ADC HAL driver. + + (+) __HAL_ADC_ENABLE : Enable the ADC peripheral + (+) __HAL_ADC_DISABLE : Disable the ADC peripheral + (+) __HAL_ADC_ENABLE_IT: Enable the ADC end of conversion interrupt + (+) __HAL_ADC_DISABLE_IT: Disable the ADC end of conversion interrupt + (+) __HAL_ADC_GET_IT_SOURCE: Check if the specified ADC interrupt source is enabled or disabled + (+) __HAL_ADC_CLEAR_FLAG: Clear the ADC's pending flags + (+) __HAL_ADC_GET_FLAG: Get the selected ADC's flag status + (+) ADC_GET_RESOLUTION: Return resolution bits in CR1 register + + [..] + (@) You can refer to the ADC HAL driver header file for more useful macros + + *** Deinitialization of ADC *** + ============================================================================== + [..] + (#) Disable the ADC interface + (++) ADC clock can be hard reset and disabled at RCC top level. + (++) Hard reset of ADC peripherals + using macro __HAL_RCC_ADC_FORCE_RESET(), __HAL_RCC_ADC_RELEASE_RESET(). + (++) ADC clock disable using the equivalent macro/functions as configuration step. + (+++) Example: + Into HAL_ADC_MspDeInit() (recommended code location) or with + other device clock parameters configuration: + (+++) HAL_RCC_GetOscConfig(&RCC_OscInitStructure); + (+++) RCC_OscInitStructure.OscillatorType = RCC_OSCILLATORTYPE_HSI; + (+++) RCC_OscInitStructure.HSIState = RCC_HSI_OFF; (if not used for system clock) + (+++) HAL_RCC_OscConfig(&RCC_OscInitStructure); + + (#) ADC pins configuration + (++) Disable the clock for the ADC GPIOs using macro __HAL_RCC_GPIOx_CLK_DISABLE() + + (#) Optionally, in case of usage of ADC with interruptions: + (++) Disable the NVIC for ADC using function HAL_NVIC_DisableIRQ(ADCx_IRQn) + + (#) Optionally, in case of usage of DMA: + (++) Deinitialize the DMA using function HAL_DMA_DeInit(). + (++) Disable the NVIC for DMA using function HAL_NVIC_DisableIRQ(DMAx_Channelx_IRQn) + *** Callback registration *** + ============================================================================== + [..] + + The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1, + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_ADC_RegisterCallback() + to register an interrupt callback. + [..] + + Function HAL_ADC_RegisterCallback() allows to register following callbacks: + (+) ConvCpltCallback : ADC conversion complete callback + (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback + (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback + (+) ErrorCallback : ADC error callback + (+) InjectedConvCpltCallback : ADC group injected conversion complete callback + (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback + (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback + (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback + (+) EndOfSamplingCallback : ADC end of sampling callback + (+) MspInitCallback : ADC Msp Init callback + (+) MspDeInitCallback : ADC Msp DeInit callback + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + + Use function HAL_ADC_UnRegisterCallback to reset a callback to the default + weak function. + [..] + + HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) ConvCpltCallback : ADC conversion complete callback + (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback + (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback + (+) ErrorCallback : ADC error callback + (+) InjectedConvCpltCallback : ADC group injected conversion complete callback + (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback + (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback + (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback + (+) EndOfSamplingCallback : ADC end of sampling callback + (+) MspInitCallback : ADC Msp Init callback + (+) MspDeInitCallback : ADC Msp DeInit callback + [..] + + By default, after the HAL_ADC_Init() and when the state is HAL_ADC_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_ADC_ConvCpltCallback(), HAL_ADC_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_ADC_Init()/ HAL_ADC_DeInit() only when + these callbacks are null (not registered beforehand). + [..] + + If MspInit or MspDeInit are not null, the HAL_ADC_Init()/ HAL_ADC_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + + Callbacks can be registered/unregistered in HAL_ADC_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_ADC_STATE_READY or HAL_ADC_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + [..] + + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_ADC_RegisterCallback() before calling HAL_ADC_DeInit() + or HAL_ADC_Init() function. + [..] + + When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup ADC ADC + * @brief ADC driver modules + * @{ + */ + +#ifdef HAL_ADC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup ADC_Private_Functions + * @{ + */ +/* Private function prototypes -----------------------------------------------*/ +static void ADC_Init(ADC_HandleTypeDef* hadc); +static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma); +static void ADC_DMAError(DMA_HandleTypeDef *hdma); +static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma); +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup ADC_Exported_Functions ADC Exported Functions + * @{ + */ + +/** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the ADC. + (+) De-initialize the ADC. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct and initializes the ADC MSP. + * + * @note This function is used to configure the global features of the ADC ( + * ClockPrescaler, Resolution, Data Alignment and number of conversion), however, + * the rest of the configuration parameters are specific to the regular + * channels group (scan mode activation, continuous mode activation, + * External trigger source and edge, DMA continuous request after the + * last transfer and End of conversion selection). + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check ADC handle */ + if(hadc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + assert_param(IS_ADC_CLOCKPRESCALER(hadc->Init.ClockPrescaler)); + assert_param(IS_ADC_RESOLUTION(hadc->Init.Resolution)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG(hadc->Init.ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(hadc->Init.DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); + assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DiscontinuousConvMode)); + + if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) + { + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + } + + if(hadc->State == HAL_ADC_STATE_RESET) + { +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + /* Init the ADC Callback settings */ + hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; /* Legacy weak callback */ + hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; /* Legacy weak callback */ + hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; /* Legacy weak callback */ + hadc->ErrorCallback = HAL_ADC_ErrorCallback; /* Legacy weak callback */ + hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; /* Legacy weak callback */ + if (hadc->MspInitCallback == NULL) + { + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hadc->MspInitCallback(hadc); +#else + /* Init the low level hardware */ + HAL_ADC_MspInit(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Initialize ADC error code */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Allocate lock resource and initialize it */ + hadc->Lock = HAL_UNLOCKED; + } + + /* Configuration of ADC parameters if previous preliminary actions are */ + /* correctly completed. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_BUSY_INTERNAL); + + /* Set ADC parameters */ + ADC_Init(hadc); + + /* Set ADC error code to none */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Set the ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_BUSY_INTERNAL, + HAL_ADC_STATE_READY); + } + else + { + tmp_hal_status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check ADC handle */ + if(hadc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_BUSY_INTERNAL); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Configuration of ADC parameters if previous preliminary actions are */ + /* correctly completed. */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + if (hadc->MspDeInitCallback == NULL) + { + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: RCC clock, NVIC */ + hadc->MspDeInitCallback(hadc); +#else + /* DeInit the low level hardware: RCC clock, NVIC */ + HAL_ADC_MspDeInit(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Set ADC error code to none */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Set ADC state */ + hadc->State = HAL_ADC_STATE_RESET; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User ADC Callback + * To be used instead of the weak predefined callback + * @param hadc Pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID + * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID + * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID + * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID + * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID + * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID + * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) + { + switch (CallbackID) + { + case HAL_ADC_CONVERSION_COMPLETE_CB_ID : + hadc->ConvCpltCallback = pCallback; + break; + + case HAL_ADC_CONVERSION_HALF_CB_ID : + hadc->ConvHalfCpltCallback = pCallback; + break; + + case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : + hadc->LevelOutOfWindowCallback = pCallback; + break; + + case HAL_ADC_ERROR_CB_ID : + hadc->ErrorCallback = pCallback; + break; + + case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : + hadc->InjectedConvCpltCallback = pCallback; + break; + + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = pCallback; + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_ADC_STATE_RESET == hadc->State) + { + switch (CallbackID) + { + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = pCallback; + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Unregister a ADC Callback + * ADC callback is redirected to the weak predefined callback + * @param hadc Pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID + * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID + * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID + * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID + * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID + * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID + * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) + { + switch (CallbackID) + { + case HAL_ADC_CONVERSION_COMPLETE_CB_ID : + hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; + break; + + case HAL_ADC_CONVERSION_HALF_CB_ID : + hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; + break; + + case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : + hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; + break; + + case HAL_ADC_ERROR_CB_ID : + hadc->ErrorCallback = HAL_ADC_ErrorCallback; + break; + + case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : + hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; + break; + + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_ADC_STATE_RESET == hadc->State) + { + switch (CallbackID) + { + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + +/** + * @brief Initializes the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion of regular channel. + (+) Stop conversion of regular channel. + (+) Start conversion of regular channel and enable interrupt. + (+) Stop conversion of regular channel and disable interrupt. + (+) Start conversion of regular channel and enable DMA transfer. + (+) Stop conversion of regular channel and disable DMA transfer. + (+) Handle ADC interrupt request. + +@endverbatim + * @{ + */ + +/** + * @brief Enables ADC and starts conversion of the regular channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC and stop conversion of regular channels. + * + * @note Caution: This function will stop also injected channels. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Poll for regular conversion complete + * @note ADC conversion flags EOS (end of sequence) and EOC (end of + * conversion) are cleared by this function. + * @note This function cannot be used in a particular setup: ADC configured + * in DMA mode and polling for end of each conversion (ADC init + * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV). + * In this case, DMA resets the flag EOC and polling cannot be + * performed on each conversion. Nevertheless, polling can still + * be performed on the complete sequence. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Verification that ADC configuration is compliant with polling for */ + /* each conversion: */ + /* Particular case is ADC configured in DMA mode and ADC sequencer with */ + /* several ranks and polling for end of each conversion. */ + /* For code simplicity sake, this particular case is generalized to */ + /* ADC configured in DMA mode and polling for end of each conversion. */ + if (HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_EOCS) && + HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_DMA) ) + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_ERROR; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check End of conversion flag */ + while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) + { + /* Check if timeout is disabled (set to infinite wait) */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) + { + /* Update ADC state machine to timeout */ + SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_TIMEOUT; + } + } + } + } + + /* Clear regular group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); + + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Return ADC state */ + return HAL_OK; +} + +/** + * @brief Poll for conversion event + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param EventType the ADC event type. + * This parameter can be one of the following values: + * @arg ADC_AWD_EVENT: ADC Analog watch Dog event. + * @arg ADC_OVR_EVENT: ADC Overrun event. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + assert_param(IS_ADC_EVENT_TYPE(EventType)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check selected event flag */ + while(!(__HAL_ADC_GET_FLAG(hadc,EventType))) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc,EventType))) + { + /* Update ADC state machine to timeout */ + SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_TIMEOUT; + } + } + } + } + + /* Analog watchdog (level out of window) event */ + if(EventType == ADC_AWD_EVENT) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); + + /* Clear ADC analog watchdog flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); + } + /* Overrun event */ + else + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_OVR); + /* Set ADC error code to overrun */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); + + /* Clear ADC overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + } + + /* Return ADC state */ + return HAL_OK; +} + + +/** + * @brief Enables the interrupt and starts ADC conversion of regular channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Enable end of conversion interrupt for regular group */ + __HAL_ADC_ENABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables the interrupt and stop ADC conversion of regular channels. + * + * @note Caution: This function will stop also injected channels. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable ADC end of conversion interrupt for regular group */ + __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handles ADC interrupt request + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc) +{ + uint32_t tmp1 = 0U, tmp2 = 0U; + + uint32_t tmp_sr = hadc->Instance->SR; + uint32_t tmp_cr1 = hadc->Instance->CR1; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); + assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); + + tmp1 = tmp_sr & ADC_FLAG_EOC; + tmp2 = tmp_cr1 & ADC_IT_EOC; + /* Check End of conversion flag for regular channels */ + if(tmp1 && tmp2) + { + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + } + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvCpltCallback(hadc); +#else + HAL_ADC_ConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear regular group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); + } + + tmp1 = tmp_sr & ADC_FLAG_JEOC; + tmp2 = tmp_cr1 & ADC_IT_JEOC; + /* Check End of conversion flag for injected channels */ + if(tmp1 && tmp2) + { + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); + } + + /* Determine whether any further conversion upcoming on group injected */ + /* by external trigger, scan sequence on going or by automatic injected */ + /* conversion from group regular (same conditions as group regular */ + /* interruption disabling above). */ + if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && + (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && + (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && + (ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) + { + /* Disable ADC end of single conversion interrupt on group injected */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->InjectedConvCpltCallback(hadc); +#else + HAL_ADCEx_InjectedConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear injected group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_JSTRT | ADC_FLAG_JEOC)); + } + + tmp1 = tmp_sr & ADC_FLAG_AWD; + tmp2 = tmp_cr1 & ADC_IT_AWD; + /* Check Analog watchdog flag */ + if(tmp1 && tmp2) + { + if(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_AWD)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); + + /* Level out of window callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->LevelOutOfWindowCallback(hadc); +#else + HAL_ADC_LevelOutOfWindowCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear the ADC analog watchdog flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); + } + } + + tmp1 = tmp_sr & ADC_FLAG_OVR; + tmp2 = tmp_cr1 & ADC_IT_OVR; + /* Check Overrun flag */ + if(tmp1 && tmp2) + { + /* Note: On STM32F4, ADC overrun can be set through other parameters */ + /* refer to description of parameter "EOCSelection" for more */ + /* details. */ + + /* Set ADC error code to overrun */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); + + /* Clear ADC overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + + /* Error callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear the Overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + } +} + +/** + * @brief Enables ADC DMA request after last transfer (Single-ADC mode) and enables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from ADC peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Check ADC DMA Mode */ + /* - disable the DMA Mode if it is already enabled */ + if((hadc->Instance->CR2 & ADC_CR2_DMA) == ADC_CR2_DMA) + { + CLEAR_BIT(hadc->Instance->CR2, ADC_CR2_DMA); + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set the DMA transfer complete callback */ + hadc->DMA_Handle->XferCpltCallback = ADC_DMAConvCplt; + + /* Set the DMA half transfer complete callback */ + hadc->DMA_Handle->XferHalfCpltCallback = ADC_DMAHalfConvCplt; + + /* Set the DMA error callback */ + hadc->DMA_Handle->XferErrorCallback = ADC_DMAError; + + + /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ + /* start (in case of SW start): */ + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Enable ADC overrun interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); + + /* Enable ADC DMA mode */ + hadc->Instance->CR2 |= ADC_CR2_DMA; + + /* Start the DMA channel */ + HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&hadc->Instance->DR, (uint32_t)pData, Length); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC DMA (Single-ADC mode) and disables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable the selected ADC DMA mode */ + hadc->Instance->CR2 &= ~ADC_CR2_DMA; + + /* Disable the DMA channel (in case of DMA in circular mode or stop while */ + /* DMA transfer is on going) */ + if (hadc->DMA_Handle->State == HAL_DMA_STATE_BUSY) + { + tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); + + /* Check if DMA channel effectively disabled */ + if (tmp_hal_status != HAL_OK) + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_DMA); + } + } + + /* Disable ADC overrun interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Gets the converted value from data register of regular channel. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval Converted value + */ +uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc) +{ + /* Return the selected ADC converted value */ + return hadc->Instance->DR; +} + +/** + * @brief Regular conversion complete callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ConvCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Regular conversion half DMA transfer callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ConvHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Analog watchdog callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_LevelOoutOfWindowCallback could be implemented in the user file + */ +} + +/** + * @brief Error ADC callback. + * @note In case of error due to overrun when using ADC with DMA transfer + * (HAL ADC handle parameter "ErrorCode" to state "HAL_ADC_ERROR_OVR"): + * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()". + * - If needed, restart a new ADC conversion using function + * "HAL_ADC_Start_DMA()" + * (this function is also clearing overrun flag) + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure regular channels. + (+) Configure injected channels. + (+) Configure multimode. + (+) Configure the analog watch dog. + +@endverbatim + * @{ + */ + + /** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param sConfig ADC configuration structure. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_CHANNEL(sConfig->Channel)); + assert_param(IS_ADC_REGULAR_RANK(sConfig->Rank)); + assert_param(IS_ADC_SAMPLE_TIME(sConfig->SamplingTime)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (sConfig->Channel > ADC_CHANNEL_9) + { + /* Clear the old sample time */ + hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfig->Channel); + + /* Set the new sample time */ + hadc->Instance->SMPR1 |= ADC_SMPR1(sConfig->SamplingTime, sConfig->Channel); + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Clear the old sample time */ + hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfig->Channel); + + /* Set the new sample time */ + hadc->Instance->SMPR2 |= ADC_SMPR2(sConfig->SamplingTime, sConfig->Channel); + } + + /* For Rank 1 to 6 */ + if (sConfig->Rank < 7U) + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR3 &= ~ADC_SQR3_RK(ADC_SQR3_SQ1, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR3 |= ADC_SQR3_RK(sConfig->Channel, sConfig->Rank); + } + /* For Rank 7 to 12 */ + else if (sConfig->Rank < 13U) + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR2 &= ~ADC_SQR2_RK(ADC_SQR2_SQ7, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR2 |= ADC_SQR2_RK(sConfig->Channel, sConfig->Rank); + } + /* For Rank 13 to 16 */ + else + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR1 &= ~ADC_SQR1_RK(ADC_SQR1_SQ13, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR1 |= ADC_SQR1_RK(sConfig->Channel, sConfig->Rank); + } + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* if ADC1 Channel_18 is selected for VBAT Channel ennable VBATE */ + if ((hadc->Instance == ADC1) && (sConfig->Channel == ADC_CHANNEL_VBAT)) + { + /* Disable the TEMPSENSOR channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ + if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) + { + tmpADC_Common->CCR &= ~ADC_CCR_TSVREFE; + } + /* Enable the VBAT channel*/ + tmpADC_Common->CCR |= ADC_CCR_VBATE; + } + + /* if ADC1 Channel_16 or Channel_18 is selected for Temperature sensor or + Channel_17 is selected for VREFINT enable TSVREFE */ + if ((hadc->Instance == ADC1) && ((sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) || (sConfig->Channel == ADC_CHANNEL_VREFINT))) + { + /* Disable the VBAT channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ + if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) + { + tmpADC_Common->CCR &= ~ADC_CCR_VBATE; + } + /* Enable the Temperature sensor and VREFINT channel*/ + tmpADC_Common->CCR |= ADC_CCR_TSVREFE; + + if(sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) + { + /* Delay for temperature sensor stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_TEMPSENSOR_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the analog watchdog. + * @note Analog watchdog thresholds can be modified while ADC conversion + * is on going. + * In this case, some constraints must be taken into account: + * The programmed threshold values are effective from the next + * ADC EOC (end of unitary conversion). + * Considering that registers write delay may happen due to + * bus activity, this might cause an uncertainty on the + * effective timing of the new programmed threshold values. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param AnalogWDGConfig pointer to an ADC_AnalogWDGConfTypeDef structure + * that contains the configuration information of ADC analog watchdog. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig) +{ +#ifdef USE_FULL_ASSERT + uint32_t tmp = 0U; +#endif /* USE_FULL_ASSERT */ + + /* Check the parameters */ + assert_param(IS_ADC_ANALOG_WATCHDOG(AnalogWDGConfig->WatchdogMode)); + assert_param(IS_ADC_CHANNEL(AnalogWDGConfig->Channel)); + assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig->ITMode)); + +#ifdef USE_FULL_ASSERT + tmp = ADC_GET_RESOLUTION(hadc); + assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->HighThreshold)); + assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->LowThreshold)); +#endif /* USE_FULL_ASSERT */ + + /* Process locked */ + __HAL_LOCK(hadc); + + if(AnalogWDGConfig->ITMode == ENABLE) + { + /* Enable the ADC Analog watchdog interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_AWD); + } + else + { + /* Disable the ADC Analog watchdog interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_AWD); + } + + /* Clear AWDEN, JAWDEN and AWDSGL bits */ + hadc->Instance->CR1 &= ~(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN | ADC_CR1_AWDEN); + + /* Set the analog watchdog enable mode */ + hadc->Instance->CR1 |= AnalogWDGConfig->WatchdogMode; + + /* Set the high threshold */ + hadc->Instance->HTR = AnalogWDGConfig->HighThreshold; + + /* Set the low threshold */ + hadc->Instance->LTR = AnalogWDGConfig->LowThreshold; + + /* Clear the Analog watchdog channel select bits */ + hadc->Instance->CR1 &= ~ADC_CR1_AWDCH; + + /* Set the Analog watchdog channel */ + hadc->Instance->CR1 |= (uint32_t)((uint16_t)(AnalogWDGConfig->Channel)); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group4 ADC Peripheral State functions + * @brief ADC Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the ADC state + (+) Check the ADC Error + +@endverbatim + * @{ + */ + +/** + * @brief return the ADC state + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL state + */ +uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc) +{ + /* Return ADC state */ + return hadc->State; +} + +/** + * @brief Return the ADC error code + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval ADC Error Code + */ +uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc) +{ + return hadc->ErrorCode; +} + +/** + * @} + */ + +/** @addtogroup ADC_Private_Functions + * @{ + */ + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct without initializing the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +static void ADC_Init(ADC_HandleTypeDef* hadc) +{ + ADC_Common_TypeDef *tmpADC_Common; + + /* Set ADC parameters */ + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set the ADC clock prescaler */ + tmpADC_Common->CCR &= ~(ADC_CCR_ADCPRE); + tmpADC_Common->CCR |= hadc->Init.ClockPrescaler; + + /* Set ADC scan mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_SCAN); + hadc->Instance->CR1 |= ADC_CR1_SCANCONV(hadc->Init.ScanConvMode); + + /* Set ADC resolution */ + hadc->Instance->CR1 &= ~(ADC_CR1_RES); + hadc->Instance->CR1 |= hadc->Init.Resolution; + + /* Set ADC data alignment */ + hadc->Instance->CR2 &= ~(ADC_CR2_ALIGN); + hadc->Instance->CR2 |= hadc->Init.DataAlign; + + /* Enable external trigger if trigger selection is different of software */ + /* start. */ + /* Note: This configuration keeps the hardware feature of parameter */ + /* ExternalTrigConvEdge "trigger edge none" equivalent to */ + /* software start. */ + if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) + { + /* Select external trigger to start conversion */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); + hadc->Instance->CR2 |= hadc->Init.ExternalTrigConv; + + /* Select external trigger polarity */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); + hadc->Instance->CR2 |= hadc->Init.ExternalTrigConvEdge; + } + else + { + /* Reset the external trigger */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); + hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); + } + + /* Enable or disable ADC continuous conversion mode */ + hadc->Instance->CR2 &= ~(ADC_CR2_CONT); + hadc->Instance->CR2 |= ADC_CR2_CONTINUOUS((uint32_t)hadc->Init.ContinuousConvMode); + + if(hadc->Init.DiscontinuousConvMode != DISABLE) + { + assert_param(IS_ADC_REGULAR_DISC_NUMBER(hadc->Init.NbrOfDiscConversion)); + + /* Enable the selected ADC regular discontinuous mode */ + hadc->Instance->CR1 |= (uint32_t)ADC_CR1_DISCEN; + + /* Set the number of channels to be converted in discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_DISCNUM); + hadc->Instance->CR1 |= ADC_CR1_DISCONTINUOUS(hadc->Init.NbrOfDiscConversion); + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_DISCEN); + } + + /* Set ADC number of conversion */ + hadc->Instance->SQR1 &= ~(ADC_SQR1_L); + hadc->Instance->SQR1 |= ADC_SQR1(hadc->Init.NbrOfConversion); + + /* Enable or disable ADC DMA continuous request */ + hadc->Instance->CR2 &= ~(ADC_CR2_DDS); + hadc->Instance->CR2 |= ADC_CR2_DMAContReq((uint32_t)hadc->Init.DMAContinuousRequests); + + /* Enable or disable ADC end of conversion selection */ + hadc->Instance->CR2 &= ~(ADC_CR2_EOCS); + hadc->Instance->CR2 |= ADC_CR2_EOCSelection(hadc->Init.EOCSelection); +} + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Retrieve ADC handle corresponding to current DMA handle */ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) + { + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvCpltCallback(hadc); +#else + HAL_ADC_ConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + } + else /* DMA and-or internal error occurred */ + { + if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) != 0UL) + { + /* Call HAL ADC Error Callback function */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + } + else + { + /* Call DMA error callback */ + hadc->DMA_Handle->XferErrorCallback(hdma); + } + } +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + /* Half conversion callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvHalfCpltCallback(hadc); +#else + HAL_ADC_ConvHalfCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAError(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hadc->State= HAL_ADC_STATE_ERROR_DMA; + /* Set ADC error code to DMA error */ + hadc->ErrorCode |= HAL_ADC_ERROR_DMA; + /* Error callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_ADC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c new file mode 100644 index 0000000..6200c83 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c @@ -0,0 +1,1112 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc_ex.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the ADC extension peripheral: + * + Extended features functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): + (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() + (##) ADC pins configuration + (+++) Enable the clock for the ADC GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE() + (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() + (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) + (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() + (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() + (+++) Configure and enable two DMA streams stream for managing data + transfer from peripheral to memory (output stream) + (+++) Associate the initialized DMA handle to the ADC DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the two DMA Streams. The output stream should have higher + priority than the input stream. + (#) Configure the ADC Prescaler, conversion resolution and data alignment + using the HAL_ADC_Init() function. + + (#) Configure the ADC Injected channels group features, use HAL_ADC_Init() + and HAL_ADC_ConfigChannel() functions. + + (#) Three operation modes are available within this driver: + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart() + (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage + user can specify the value of timeout according to his end application + (+) To read the ADC converted values, use the HAL_ADCEx_InjectedGetValue() function. + (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart_IT() + (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine + (+) At ADC end of conversion HAL_ADCEx_InjectedConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADCEx_InjectedConvCpltCallback + (+) In case of ADC Error, HAL_ADCEx_InjectedErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADCEx_InjectedErrorCallback + (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop_IT() + + *** Multi mode ADCs Regular channels configuration *** + ====================================================== + [..] + (+) Select the Multi mode ADC regular channels features (dual or triple mode) + and configure the DMA mode using HAL_ADCEx_MultiModeConfigChannel() functions. + (+) Start the ADC peripheral using HAL_ADCEx_MultiModeStart_DMA(), at this stage the user specify the length + of data to be transferred at each end of conversion + (+) Read the ADCs converted values using the HAL_ADCEx_MultiModeGetValue() function. + + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup ADCEx ADCEx + * @brief ADC Extended driver modules + * @{ + */ + +#ifdef HAL_ADC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup ADCEx_Private_Functions + * @{ + */ +/* Private function prototypes -----------------------------------------------*/ +static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma); +static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma); +static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup ADCEx_Exported_Functions ADC Exported Functions + * @{ + */ + +/** @defgroup ADCEx_Exported_Functions_Group1 Extended features functions + * @brief Extended features functions + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion of injected channel. + (+) Stop conversion of injected channel. + (+) Start multimode and enable DMA transfer. + (+) Stop multimode and disable DMA transfer. + (+) Get result of injected channel conversion. + (+) Get result of multimode conversion. + (+) Configure injected channels. + (+) Configure multimode. + +@endverbatim + * @{ + */ + +/** + * @brief Enables the selected ADC software start conversion of the injected channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + uint32_t tmp1 = 0U, tmp2 = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to injected group conversion results */ + /* - Set state bitfield related to injected operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, + HAL_ADC_STATE_INJ_BUSY); + + /* Check if a regular conversion is ongoing */ + /* Note: On this device, there is no ADC error code fields related to */ + /* conversions on group injected only. In case of conversion on */ + /* going on group regular, no error code is reset. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Clear injected group conversion flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if(tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + else + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if((hadc->Instance == ADC1) && tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Enables the interrupt and starts ADC conversion of injected channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + uint32_t tmp1 = 0U, tmp2 = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to injected group conversion results */ + /* - Set state bitfield related to injected operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, + HAL_ADC_STATE_INJ_BUSY); + + /* Check if a regular conversion is ongoing */ + /* Note: On this device, there is no ADC error code fields related to */ + /* conversions on group injected only. In case of conversion on */ + /* going on group regular, no error code is reset. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Clear injected group conversion flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Enable end of conversion interrupt for injected channels */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if(tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + else + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if((hadc->Instance == ADC1) && tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop conversion of injected channels. Disable ADC peripheral if + * no regular conversion is on going. + * @note If ADC must be disabled and if conversion is on going on + * regular group, function HAL_ADC_Stop must be used to stop both + * injected and regular groups, and disable the ADC. + * @note If injected group mode auto-injection is enabled, + * function HAL_ADC_Stop must be used. + * @note In case of auto-injection mode, HAL_ADC_Stop must be used. + * @param hadc ADC handle + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion and disable ADC peripheral */ + /* Conditioned to: */ + /* - No conversion on the other group (regular group) is intended to */ + /* continue (injected and regular groups stop conversion and ADC disable */ + /* are common) */ + /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ + if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && + HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) + { + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + tmp_hal_status = HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Poll for injected conversion complete + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check End of conversion flag */ + while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) + { + hadc->State= HAL_ADC_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hadc); + return HAL_TIMEOUT; + } + } + } + } + + /* Clear injected group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JSTRT | ADC_FLAG_JEOC); + + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); + + /* Determine whether any further conversion upcoming on group injected */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && + (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && + (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && + (ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) + { + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Return ADC state */ + return HAL_OK; +} + +/** + * @brief Stop conversion of injected channels, disable interruption of + * end-of-conversion. Disable ADC peripheral if no regular conversion + * is on going. + * @note If ADC must be disabled and if conversion is on going on + * regular group, function HAL_ADC_Stop must be used to stop both + * injected and regular groups, and disable the ADC. + * @note If injected group mode auto-injection is enabled, + * function HAL_ADC_Stop must be used. + * @param hadc ADC handle + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion and disable ADC peripheral */ + /* Conditioned to: */ + /* - No conversion on the other group (regular group) is intended to */ + /* continue (injected and regular groups stop conversion and ADC disable */ + /* are common) */ + /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ + if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && + HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) + { + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable ADC end of conversion interrupt for injected channels */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + tmp_hal_status = HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Gets the converted value from data register of injected channel. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param InjectedRank the ADC injected rank. + * This parameter can be one of the following values: + * @arg ADC_INJECTED_RANK_1: Injected Channel1 selected + * @arg ADC_INJECTED_RANK_2: Injected Channel2 selected + * @arg ADC_INJECTED_RANK_3: Injected Channel3 selected + * @arg ADC_INJECTED_RANK_4: Injected Channel4 selected + * @retval None + */ +uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank) +{ + __IO uint32_t tmp = 0U; + + /* Check the parameters */ + assert_param(IS_ADC_INJECTED_RANK(InjectedRank)); + + /* Clear injected group conversion flag to have similar behaviour as */ + /* regular group: reading data register also clears end of conversion flag. */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Return the selected ADC converted value */ + switch(InjectedRank) + { + case ADC_INJECTED_RANK_4: + { + tmp = hadc->Instance->JDR4; + } + break; + case ADC_INJECTED_RANK_3: + { + tmp = hadc->Instance->JDR3; + } + break; + case ADC_INJECTED_RANK_2: + { + tmp = hadc->Instance->JDR2; + } + break; + case ADC_INJECTED_RANK_1: + { + tmp = hadc->Instance->JDR1; + } + break; + default: + break; + } + return tmp; +} + +/** + * @brief Enables ADC DMA request after last transfer (Multi-ADC mode) and enables ADC peripheral + * + * @note Caution: This function must be used only with the ADC master. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param pData Pointer to buffer in which transferred from ADC peripheral to memory will be stored. + * @param Length The length of data to be transferred from ADC peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for temperature sensor stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Set the DMA transfer complete callback */ + hadc->DMA_Handle->XferCpltCallback = ADC_MultiModeDMAConvCplt; + + /* Set the DMA half transfer complete callback */ + hadc->DMA_Handle->XferHalfCpltCallback = ADC_MultiModeDMAHalfConvCplt; + + /* Set the DMA error callback */ + hadc->DMA_Handle->XferErrorCallback = ADC_MultiModeDMAError ; + + /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ + /* start (in case of SW start): */ + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC); + + /* Enable ADC overrun interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + if (hadc->Init.DMAContinuousRequests != DISABLE) + { + /* Enable the selected ADC DMA request after last transfer */ + tmpADC_Common->CCR |= ADC_CCR_DDS; + } + else + { + /* Disable the selected ADC EOC rising on each regular channel conversion */ + tmpADC_Common->CCR &= ~ADC_CCR_DDS; + } + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&tmpADC_Common->CDR, (uint32_t)pData, Length); + + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC DMA (multi-ADC mode) and disables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable the selected ADC DMA mode for multimode */ + tmpADC_Common->CCR &= ~ADC_CCR_DDS; + + /* Disable the DMA channel (in case of DMA in circular mode or stop while */ + /* DMA transfer is on going) */ + tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); + + /* Disable ADC overrun interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Returns the last ADC1, ADC2 and ADC3 regular conversions results + * data in the selected multi mode. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval The converted data value. + */ +uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc) +{ + ADC_Common_TypeDef *tmpADC_Common; + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Return the multi mode conversion value */ + return tmpADC_Common->CDR; +} + +/** + * @brief Injected conversion complete callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_InjectedConvCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param sConfigInjected ADC configuration structure for injected channel. + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc, ADC_InjectionConfTypeDef* sConfigInjected) +{ + +#ifdef USE_FULL_ASSERT + uint32_t tmp = 0U; + +#endif /* USE_FULL_ASSERT */ + + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_CHANNEL(sConfigInjected->InjectedChannel)); + assert_param(IS_ADC_INJECTED_RANK(sConfigInjected->InjectedRank)); + assert_param(IS_ADC_SAMPLE_TIME(sConfigInjected->InjectedSamplingTime)); + assert_param(IS_ADC_EXT_INJEC_TRIG(sConfigInjected->ExternalTrigInjecConv)); + assert_param(IS_ADC_INJECTED_LENGTH(sConfigInjected->InjectedNbrOfConversion)); + assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->AutoInjectedConv)); + assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->InjectedDiscontinuousConvMode)); + +#ifdef USE_FULL_ASSERT + tmp = ADC_GET_RESOLUTION(hadc); + assert_param(IS_ADC_RANGE(tmp, sConfigInjected->InjectedOffset)); +#endif /* USE_FULL_ASSERT */ + + if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) + { + assert_param(IS_ADC_EXT_INJEC_TRIG_EDGE(sConfigInjected->ExternalTrigInjecConvEdge)); + } + + /* Process locked */ + __HAL_LOCK(hadc); + + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (sConfigInjected->InjectedChannel > ADC_CHANNEL_9) + { + /* Clear the old sample time */ + hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfigInjected->InjectedChannel); + + /* Set the new sample time */ + hadc->Instance->SMPR1 |= ADC_SMPR1(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Clear the old sample time */ + hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfigInjected->InjectedChannel); + + /* Set the new sample time */ + hadc->Instance->SMPR2 |= ADC_SMPR2(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); + } + + /*---------------------------- ADCx JSQR Configuration -----------------*/ + hadc->Instance->JSQR &= ~(ADC_JSQR_JL); + hadc->Instance->JSQR |= ADC_SQR1(sConfigInjected->InjectedNbrOfConversion); + + /* Rank configuration */ + + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->JSQR &= ~ADC_JSQR(ADC_JSQR_JSQ1, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->JSQR |= ADC_JSQR(sConfigInjected->InjectedChannel, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); + + /* Enable external trigger if trigger selection is different of software */ + /* start. */ + /* Note: This configuration keeps the hardware feature of parameter */ + /* ExternalTrigConvEdge "trigger edge none" equivalent to */ + /* software start. */ + if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) + { + /* Select external trigger to start conversion */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); + hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConv; + + /* Select external trigger polarity */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); + hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConvEdge; + } + else + { + /* Reset the external trigger */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); + } + + if (sConfigInjected->AutoInjectedConv != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + hadc->Instance->CR1 |= ADC_CR1_JAUTO; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + hadc->Instance->CR1 &= ~(ADC_CR1_JAUTO); + } + + if (sConfigInjected->InjectedDiscontinuousConvMode != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + hadc->Instance->CR1 |= ADC_CR1_JDISCEN; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_JDISCEN); + } + + switch(sConfigInjected->InjectedRank) + { + case 1U: + /* Set injected channel 1 offset */ + hadc->Instance->JOFR1 &= ~(ADC_JOFR1_JOFFSET1); + hadc->Instance->JOFR1 |= sConfigInjected->InjectedOffset; + break; + case 2U: + /* Set injected channel 2 offset */ + hadc->Instance->JOFR2 &= ~(ADC_JOFR2_JOFFSET2); + hadc->Instance->JOFR2 |= sConfigInjected->InjectedOffset; + break; + case 3U: + /* Set injected channel 3 offset */ + hadc->Instance->JOFR3 &= ~(ADC_JOFR3_JOFFSET3); + hadc->Instance->JOFR3 |= sConfigInjected->InjectedOffset; + break; + default: + /* Set injected channel 4 offset */ + hadc->Instance->JOFR4 &= ~(ADC_JOFR4_JOFFSET4); + hadc->Instance->JOFR4 |= sConfigInjected->InjectedOffset; + break; + } + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* if ADC1 Channel_18 is selected enable VBAT Channel */ + if ((hadc->Instance == ADC1) && (sConfigInjected->InjectedChannel == ADC_CHANNEL_VBAT)) + { + /* Enable the VBAT channel*/ + tmpADC_Common->CCR |= ADC_CCR_VBATE; + } + + /* if ADC1 Channel_16 or Channel_17 is selected enable TSVREFE Channel(Temperature sensor and VREFINT) */ + if ((hadc->Instance == ADC1) && ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) || (sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT))) + { + /* Enable the TSVREFE channel*/ + tmpADC_Common->CCR |= ADC_CCR_TSVREFE; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the ADC multi-mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param multimode pointer to an ADC_MultiModeTypeDef structure that contains + * the configuration information for multimode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode) +{ + + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_MODE(multimode->Mode)); + assert_param(IS_ADC_DMA_ACCESS_MODE(multimode->DMAAccessMode)); + assert_param(IS_ADC_SAMPLING_DELAY(multimode->TwoSamplingDelay)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set ADC mode */ + tmpADC_Common->CCR &= ~(ADC_CCR_MULTI); + tmpADC_Common->CCR |= multimode->Mode; + + /* Set the ADC DMA access mode */ + tmpADC_Common->CCR &= ~(ADC_CCR_DMA); + tmpADC_Common->CCR |= multimode->DMAAccessMode; + + /* Set delay between two sampling phases */ + tmpADC_Common->CCR &= ~(ADC_CCR_DELAY); + tmpADC_Common->CCR |= multimode->TwoSamplingDelay; + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Retrieve ADC handle corresponding to current DMA handle */ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) + { + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ + HAL_ADC_ConvCpltCallback(hadc); + } + else + { + /* Call DMA error callback */ + hadc->DMA_Handle->XferErrorCallback(hdma); + } +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + /* Conversion complete callback */ + HAL_ADC_ConvHalfCpltCallback(hadc); +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hadc->State= HAL_ADC_STATE_ERROR_DMA; + /* Set ADC error code to DMA error */ + hadc->ErrorCode |= HAL_ADC_ERROR_DMA; + HAL_ADC_ErrorCallback(hadc); +} + +/** + * @} + */ + +#endif /* HAL_ADC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c index 4abdc60..a47bfa8 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c @@ -1,2462 +1,2462 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.c - * @author MCD Application Team - * @brief CAN HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Controller Area Network (CAN) peripheral: - * + Initialization and de-initialization functions - * + Configuration functions - * + Control functions - * + Interrupts management - * + Callbacks functions - * + Peripheral State and Error functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the CAN low level resources by implementing the - HAL_CAN_MspInit(): - (++) Enable the CAN interface clock using __HAL_RCC_CANx_CLK_ENABLE() - (++) Configure CAN pins - (+++) Enable the clock for the CAN GPIOs - (+++) Configure CAN pins as alternate function open-drain - (++) In case of using interrupts (e.g. HAL_CAN_ActivateNotification()) - (+++) Configure the CAN interrupt priority using - HAL_NVIC_SetPriority() - (+++) Enable the CAN IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In CAN IRQ handler, call HAL_CAN_IRQHandler() - - (#) Initialize the CAN peripheral using HAL_CAN_Init() function. This - function resorts to HAL_CAN_MspInit() for low-level initialization. - - (#) Configure the reception filters using the following configuration - functions: - (++) HAL_CAN_ConfigFilter() - - (#) Start the CAN module using HAL_CAN_Start() function. At this level - the node is active on the bus: it receive messages, and can send - messages. - - (#) To manage messages transmission, the following Tx control functions - can be used: - (++) HAL_CAN_AddTxMessage() to request transmission of a new - message. - (++) HAL_CAN_AbortTxRequest() to abort transmission of a pending - message. - (++) HAL_CAN_GetTxMailboxesFreeLevel() to get the number of free Tx - mailboxes. - (++) HAL_CAN_IsTxMessagePending() to check if a message is pending - in a Tx mailbox. - (++) HAL_CAN_GetTxTimestamp() to get the timestamp of Tx message - sent, if time triggered communication mode is enabled. - - (#) When a message is received into the CAN Rx FIFOs, it can be retrieved - using the HAL_CAN_GetRxMessage() function. The function - HAL_CAN_GetRxFifoFillLevel() allows to know how many Rx message are - stored in the Rx Fifo. - - (#) Calling the HAL_CAN_Stop() function stops the CAN module. - - (#) The deinitialization is achieved with HAL_CAN_DeInit() function. - - - *** Polling mode operation *** - ============================== - [..] - (#) Reception: - (++) Monitor reception of message using HAL_CAN_GetRxFifoFillLevel() - until at least one message is received. - (++) Then get the message using HAL_CAN_GetRxMessage(). - - (#) Transmission: - (++) Monitor the Tx mailboxes availability until at least one Tx - mailbox is free, using HAL_CAN_GetTxMailboxesFreeLevel(). - (++) Then request transmission of a message using - HAL_CAN_AddTxMessage(). - - - *** Interrupt mode operation *** - ================================ - [..] - (#) Notifications are activated using HAL_CAN_ActivateNotification() - function. Then, the process can be controlled through the - available user callbacks: HAL_CAN_xxxCallback(), using same APIs - HAL_CAN_GetRxMessage() and HAL_CAN_AddTxMessage(). - - (#) Notifications can be deactivated using - HAL_CAN_DeactivateNotification() function. - - (#) Special care should be taken for CAN_IT_RX_FIFO0_MSG_PENDING and - CAN_IT_RX_FIFO1_MSG_PENDING notifications. These notifications trig - the callbacks HAL_CAN_RxFIFO0MsgPendingCallback() and - HAL_CAN_RxFIFO1MsgPendingCallback(). User has two possible options - here. - (++) Directly get the Rx message in the callback, using - HAL_CAN_GetRxMessage(). - (++) Or deactivate the notification in the callback without - getting the Rx message. The Rx message can then be got later - using HAL_CAN_GetRxMessage(). Once the Rx message have been - read, the notification can be activated again. - - - *** Sleep mode *** - ================== - [..] - (#) The CAN peripheral can be put in sleep mode (low power), using - HAL_CAN_RequestSleep(). The sleep mode will be entered as soon as the - current CAN activity (transmission or reception of a CAN frame) will - be completed. - - (#) A notification can be activated to be informed when the sleep mode - will be entered. - - (#) It can be checked if the sleep mode is entered using - HAL_CAN_IsSleepActive(). - Note that the CAN state (accessible from the API HAL_CAN_GetState()) - is HAL_CAN_STATE_SLEEP_PENDING as soon as the sleep mode request is - submitted (the sleep mode is not yet entered), and become - HAL_CAN_STATE_SLEEP_ACTIVE when the sleep mode is effective. - - (#) The wake-up from sleep mode can be triggered by two ways: - (++) Using HAL_CAN_WakeUp(). When returning from this function, - the sleep mode is exited (if return status is HAL_OK). - (++) When a start of Rx CAN frame is detected by the CAN peripheral, - if automatic wake up mode is enabled. - - *** Callback registration *** - ============================================= - - The compilation define USE_HAL_CAN_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Function HAL_CAN_RegisterCallback() to register an interrupt callback. - - Function HAL_CAN_RegisterCallback() allows to register following callbacks: - (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. - (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. - (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. - (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. - (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. - (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. - (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. - (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. - (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. - (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. - (+) SleepCallback : Sleep Callback. - (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. - (+) ErrorCallback : Error Callback. - (+) MspInitCallback : CAN MspInit. - (+) MspDeInitCallback : CAN MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_CAN_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_CAN_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. - (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. - (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. - (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. - (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. - (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. - (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. - (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. - (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. - (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. - (+) SleepCallback : Sleep Callback. - (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. - (+) ErrorCallback : Error Callback. - (+) MspInitCallback : CAN MspInit. - (+) MspDeInitCallback : CAN MspDeInit. - - By default, after the HAL_CAN_Init() and when the state is HAL_CAN_STATE_RESET, - all callbacks are set to the corresponding weak functions: - example HAL_CAN_ErrorCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the HAL_CAN_Init()/ HAL_CAN_DeInit() only when - these callbacks are null (not registered beforehand). - if not, MspInit or MspDeInit are not null, the HAL_CAN_Init()/ HAL_CAN_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in HAL_CAN_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_CAN_STATE_READY or HAL_CAN_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_CAN_RegisterCallback() before calling HAL_CAN_DeInit() - or HAL_CAN_Init() function. - - When The compilation define USE_HAL_CAN_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(CAN1) - -/** @defgroup CAN CAN - * @brief CAN driver modules - * @{ - */ - -#ifdef HAL_CAN_MODULE_ENABLED - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #error "The CAN driver cannot be used with its legacy, Please enable only one CAN module at once" -#endif - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_TIMEOUT_VALUE 10U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_Init : Initialize and configure the CAN. - (+) HAL_CAN_DeInit : De-initialize the CAN. - (+) HAL_CAN_MspInit : Initialize the CAN MSP. - (+) HAL_CAN_MspDeInit : DeInitialize the CAN MSP. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the CAN peripheral according to the specified - * parameters in the CAN_InitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - /* Check CAN handle */ - if (hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TimeTriggeredMode)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoBusOff)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoWakeUp)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoRetransmission)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ReceiveFifoLocked)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TransmitFifoPriority)); - assert_param(IS_CAN_MODE(hcan->Init.Mode)); - assert_param(IS_CAN_SJW(hcan->Init.SyncJumpWidth)); - assert_param(IS_CAN_BS1(hcan->Init.TimeSeg1)); - assert_param(IS_CAN_BS2(hcan->Init.TimeSeg2)); - assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - if (hcan->State == HAL_CAN_STATE_RESET) - { - /* Reset callbacks to legacy functions */ - hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; /* Legacy weak RxFifo0MsgPendingCallback */ - hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; /* Legacy weak RxFifo0FullCallback */ - hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; /* Legacy weak RxFifo1MsgPendingCallback */ - hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; /* Legacy weak RxFifo1FullCallback */ - hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; /* Legacy weak TxMailbox0CompleteCallback */ - hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; /* Legacy weak TxMailbox1CompleteCallback */ - hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; /* Legacy weak TxMailbox2CompleteCallback */ - hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; /* Legacy weak TxMailbox0AbortCallback */ - hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; /* Legacy weak TxMailbox1AbortCallback */ - hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; /* Legacy weak TxMailbox2AbortCallback */ - hcan->SleepCallback = HAL_CAN_SleepCallback; /* Legacy weak SleepCallback */ - hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; /* Legacy weak WakeUpFromRxMsgCallback */ - hcan->ErrorCallback = HAL_CAN_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hcan->MspInitCallback == NULL) - { - hcan->MspInitCallback = HAL_CAN_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware: CLOCK, NVIC */ - hcan->MspInitCallback(hcan); - } - -#else - if (hcan->State == HAL_CAN_STATE_RESET) - { - /* Init the low level hardware: CLOCK, NVIC */ - HAL_CAN_MspInit(hcan); - } -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ - - /* Request initialisation */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait initialisation acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) - { - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Exit from sleep mode */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check Sleep mode leave acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Set the time triggered communication mode */ - if (hcan->Init.TimeTriggeredMode == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); - } - - /* Set the automatic bus-off management */ - if (hcan->Init.AutoBusOff == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); - } - - /* Set the automatic wake-up mode */ - if (hcan->Init.AutoWakeUp == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); - } - - /* Set the automatic retransmission */ - if (hcan->Init.AutoRetransmission == ENABLE) - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_NART); - } - else - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_NART); - } - - /* Set the receive FIFO locked mode */ - if (hcan->Init.ReceiveFifoLocked == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); - } - - /* Set the transmit FIFO priority */ - if (hcan->Init.TransmitFifoPriority == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); - } - - /* Set the bit timing register */ - WRITE_REG(hcan->Instance->BTR, (uint32_t)(hcan->Init.Mode | - hcan->Init.SyncJumpWidth | - hcan->Init.TimeSeg1 | - hcan->Init.TimeSeg2 | - (hcan->Init.Prescaler - 1U))); - - /* Initialize the error code */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Initialize the CAN state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Deinitializes the CAN peripheral registers to their default - * reset values. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan) -{ - /* Check CAN handle */ - if (hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - - /* Stop the CAN module */ - (void)HAL_CAN_Stop(hcan); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - if (hcan->MspDeInitCallback == NULL) - { - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: CLOCK, NVIC */ - hcan->MspDeInitCallback(hcan); - -#else - /* DeInit the low level hardware: CLOCK, NVIC */ - HAL_CAN_MspDeInit(hcan); -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ - - /* Reset the CAN peripheral */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_RESET); - - /* Reset the CAN ErrorCode */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_RESET; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspDeInit could be implemented in the user file - */ -} - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/** - * @brief Register a CAN CallBack. - * To be used instead of the weak predefined callback - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for CAN module - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID - * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID - * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID - * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID - * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID - * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - if (hcan->State == HAL_CAN_STATE_READY) - { - switch (CallbackID) - { - case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : - hcan->TxMailbox0CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : - hcan->TxMailbox1CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : - hcan->TxMailbox2CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : - hcan->TxMailbox0AbortCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : - hcan->TxMailbox1AbortCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : - hcan->TxMailbox2AbortCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : - hcan->RxFifo0MsgPendingCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO0_FULL_CB_ID : - hcan->RxFifo0FullCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : - hcan->RxFifo1MsgPendingCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO1_FULL_CB_ID : - hcan->RxFifo1FullCallback = pCallback; - break; - - case HAL_CAN_SLEEP_CB_ID : - hcan->SleepCallback = pCallback; - break; - - case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : - hcan->WakeUpFromRxMsgCallback = pCallback; - break; - - case HAL_CAN_ERROR_CB_ID : - hcan->ErrorCallback = pCallback; - break; - - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = pCallback; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcan->State == HAL_CAN_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = pCallback; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} - -/** - * @brief Unregister a CAN CallBack. - * CAN callback is redirected to the weak predefined callback - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for CAN module - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID - * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID - * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID - * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID - * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID - * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (hcan->State == HAL_CAN_STATE_READY) - { - switch (CallbackID) - { - case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : - hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : - hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : - hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : - hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; - break; - - case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : - hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; - break; - - case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : - hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; - break; - - case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : - hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; - break; - - case HAL_CAN_RX_FIFO0_FULL_CB_ID : - hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; - break; - - case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : - hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; - break; - - case HAL_CAN_RX_FIFO1_FULL_CB_ID : - hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; - break; - - case HAL_CAN_SLEEP_CB_ID : - hcan->SleepCallback = HAL_CAN_SleepCallback; - break; - - case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : - hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; - break; - - case HAL_CAN_ERROR_CB_ID : - hcan->ErrorCallback = HAL_CAN_ErrorCallback; - break; - - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = HAL_CAN_MspInit; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcan->State == HAL_CAN_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = HAL_CAN_MspInit; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group2 Configuration functions - * @brief Configuration functions. - * -@verbatim - ============================================================================== - ##### Configuration functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_ConfigFilter : Configure the CAN reception filters - -@endverbatim - * @{ - */ - -/** - * @brief Configures the CAN reception filter according to the specified - * parameters in the CAN_FilterInitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param sFilterConfig pointer to a CAN_FilterTypeDef structure that - * contains the filter configuration information. - * @retval None - */ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig) -{ - uint32_t filternbrbitpos; - CAN_TypeDef *can_ip = hcan->Instance; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check the parameters */ - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdHigh)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdLow)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdHigh)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdLow)); - assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); - assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); - assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); - assert_param(IS_CAN_FILTER_ACTIVATION(sFilterConfig->FilterActivation)); - -#if defined(CAN3) - /* Check the CAN instance */ - if (hcan->Instance == CAN3) - { - /* CAN3 is single instance with 14 dedicated filters banks */ - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); - } - else - { - /* CAN1 and CAN2 are dual instances with 28 common filters banks */ - /* Select master instance to access the filter banks */ - can_ip = CAN1; - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); - } -#elif defined(CAN2) - /* CAN1 and CAN2 are dual instances with 28 common filters banks */ - /* Select master instance to access the filter banks */ - can_ip = CAN1; - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); -#else - /* CAN1 is single instance with 14 dedicated filters banks */ - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); -#endif - - /* Initialisation mode for the filter */ - SET_BIT(can_ip->FMR, CAN_FMR_FINIT); - -#if defined(CAN3) - /* Check the CAN instance */ - if (can_ip == CAN1) - { - /* Select the start filter number of CAN2 slave instance */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); - SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); - } - -#elif defined(CAN2) - /* Select the start filter number of CAN2 slave instance */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); - SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); - -#endif - /* Convert filter number into bit position */ - filternbrbitpos = (uint32_t)1 << (sFilterConfig->FilterBank & 0x1FU); - - /* Filter Deactivation */ - CLEAR_BIT(can_ip->FA1R, filternbrbitpos); - - /* Filter Scale */ - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) - { - /* 16-bit scale for the filter */ - CLEAR_BIT(can_ip->FS1R, filternbrbitpos); - - /* First 16-bit identifier and First 16-bit mask */ - /* Or First 16-bit identifier and Second 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - - /* Second 16-bit identifier and Second 16-bit mask */ - /* Or Third 16-bit identifier and Fourth 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); - } - - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) - { - /* 32-bit scale for the filter */ - SET_BIT(can_ip->FS1R, filternbrbitpos); - - /* 32-bit identifier or First 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - - /* 32-bit mask or Second 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); - } - - /* Filter Mode */ - if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) - { - /* Id/Mask mode for the filter*/ - CLEAR_BIT(can_ip->FM1R, filternbrbitpos); - } - else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ - { - /* Identifier list mode for the filter*/ - SET_BIT(can_ip->FM1R, filternbrbitpos); - } - - /* Filter FIFO assignment */ - if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) - { - /* FIFO 0 assignation for the filter */ - CLEAR_BIT(can_ip->FFA1R, filternbrbitpos); - } - else - { - /* FIFO 1 assignation for the filter */ - SET_BIT(can_ip->FFA1R, filternbrbitpos); - } - - /* Filter activation */ - if (sFilterConfig->FilterActivation == CAN_FILTER_ENABLE) - { - SET_BIT(can_ip->FA1R, filternbrbitpos); - } - - /* Leave the initialisation mode for the filter */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_FINIT); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group3 Control functions - * @brief Control functions - * -@verbatim - ============================================================================== - ##### Control functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_Start : Start the CAN module - (+) HAL_CAN_Stop : Stop the CAN module - (+) HAL_CAN_RequestSleep : Request sleep mode entry. - (+) HAL_CAN_WakeUp : Wake up from sleep mode. - (+) HAL_CAN_IsSleepActive : Check is sleep mode is active. - (+) HAL_CAN_AddTxMessage : Add a message to the Tx mailboxes - and activate the corresponding - transmission request - (+) HAL_CAN_AbortTxRequest : Abort transmission request - (+) HAL_CAN_GetTxMailboxesFreeLevel : Return Tx mailboxes free level - (+) HAL_CAN_IsTxMessagePending : Check if a transmission request is - pending on the selected Tx mailbox - (+) HAL_CAN_GetRxMessage : Get a CAN frame from the Rx FIFO - (+) HAL_CAN_GetRxFifoFillLevel : Return Rx FIFO fill level - -@endverbatim - * @{ - */ - -/** - * @brief Start the CAN module. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - if (hcan->State == HAL_CAN_STATE_READY) - { - /* Change CAN peripheral state */ - hcan->State = HAL_CAN_STATE_LISTENING; - - /* Request leave initialisation */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Reset the CAN ErrorCode */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_READY; - - return HAL_ERROR; - } -} - -/** - * @brief Stop the CAN module and enable access to configuration registers. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - if (hcan->State == HAL_CAN_STATE_LISTENING) - { - /* Request initialisation */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Exit from sleep mode */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Change CAN peripheral state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_STARTED; - - return HAL_ERROR; - } -} - -/** - * @brief Request the sleep mode (low power) entry. - * When returning from this function, Sleep mode will be entered - * as soon as the current CAN activity (transmission or reception - * of a CAN frame) has been completed. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Request Sleep mode */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - /* Return function status */ - return HAL_ERROR; - } -} - -/** - * @brief Wake up from sleep mode. - * When returning with HAL_OK status from this function, Sleep mode - * is exited. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan) -{ - __IO uint32_t count = 0; - uint32_t timeout = 1000000U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Wake up request */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Wait sleep mode is exited */ - do - { - /* Increment counter */ - count++; - - /* Check if timeout is reached */ - if (count > timeout) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - return HAL_ERROR; - } - } - while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Check is sleep mode is active. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval Status - * - 0 : Sleep mode is not active. - * - 1 : Sleep mode is active. - */ -uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan) -{ - uint32_t status = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Sleep mode */ - if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - status = 1U; - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Add a message to the first free Tx mailbox and activate the - * corresponding transmission request. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param pHeader pointer to a CAN_TxHeaderTypeDef structure. - * @param aData array containing the payload of the Tx frame. - * @param pTxMailbox pointer to a variable where the function will return - * the TxMailbox used to store the Tx message. - * This parameter can be a value of @arg CAN_Tx_Mailboxes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox) -{ - uint32_t transmitmailbox; - HAL_CAN_StateTypeDef state = hcan->State; - uint32_t tsr = READ_REG(hcan->Instance->TSR); - - /* Check the parameters */ - assert_param(IS_CAN_IDTYPE(pHeader->IDE)); - assert_param(IS_CAN_RTR(pHeader->RTR)); - assert_param(IS_CAN_DLC(pHeader->DLC)); - if (pHeader->IDE == CAN_ID_STD) - { - assert_param(IS_CAN_STDID(pHeader->StdId)); - } - else - { - assert_param(IS_CAN_EXTID(pHeader->ExtId)); - } - assert_param(IS_FUNCTIONAL_STATE(pHeader->TransmitGlobalTime)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check that all the Tx mailboxes are not full */ - if (((tsr & CAN_TSR_TME0) != 0U) || - ((tsr & CAN_TSR_TME1) != 0U) || - ((tsr & CAN_TSR_TME2) != 0U)) - { - /* Select an empty transmit mailbox */ - transmitmailbox = (tsr & CAN_TSR_CODE) >> CAN_TSR_CODE_Pos; - - /* Check transmit mailbox value */ - if (transmitmailbox > 2U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INTERNAL; - - return HAL_ERROR; - } - - /* Store the Tx mailbox */ - *pTxMailbox = (uint32_t)1 << transmitmailbox; - - /* Set up the Id */ - if (pHeader->IDE == CAN_ID_STD) - { - hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->StdId << CAN_TI0R_STID_Pos) | - pHeader->RTR); - } - else - { - hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->ExtId << CAN_TI0R_EXID_Pos) | - pHeader->IDE | - pHeader->RTR); - } - - /* Set up the DLC */ - hcan->Instance->sTxMailBox[transmitmailbox].TDTR = (pHeader->DLC); - - /* Set up the Transmit Global Time mode */ - if (pHeader->TransmitGlobalTime == ENABLE) - { - SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TDTR, CAN_TDT0R_TGT); - } - - /* Set up the data field */ - WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDHR, - ((uint32_t)aData[7] << CAN_TDH0R_DATA7_Pos) | - ((uint32_t)aData[6] << CAN_TDH0R_DATA6_Pos) | - ((uint32_t)aData[5] << CAN_TDH0R_DATA5_Pos) | - ((uint32_t)aData[4] << CAN_TDH0R_DATA4_Pos)); - WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDLR, - ((uint32_t)aData[3] << CAN_TDL0R_DATA3_Pos) | - ((uint32_t)aData[2] << CAN_TDL0R_DATA2_Pos) | - ((uint32_t)aData[1] << CAN_TDL0R_DATA1_Pos) | - ((uint32_t)aData[0] << CAN_TDL0R_DATA0_Pos)); - - /* Request transmission */ - SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TIR, CAN_TI0R_TXRQ); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Abort transmission requests - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailboxes List of the Tx Mailboxes to abort. - * This parameter can be any combination of @arg CAN_Tx_Mailboxes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Tx Mailbox 0 */ - if ((TxMailboxes & CAN_TX_MAILBOX0) != 0U) - { - /* Add cancellation request for Tx Mailbox 0 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ0); - } - - /* Check Tx Mailbox 1 */ - if ((TxMailboxes & CAN_TX_MAILBOX1) != 0U) - { - /* Add cancellation request for Tx Mailbox 1 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ1); - } - - /* Check Tx Mailbox 2 */ - if ((TxMailboxes & CAN_TX_MAILBOX2) != 0U) - { - /* Add cancellation request for Tx Mailbox 2 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ2); - } - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Return Tx Mailboxes free level: number of free Tx Mailboxes. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval Number of free Tx Mailboxes. - */ -uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan) -{ - uint32_t freelevel = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Tx Mailbox 0 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME0) != 0U) - { - freelevel++; - } - - /* Check Tx Mailbox 1 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME1) != 0U) - { - freelevel++; - } - - /* Check Tx Mailbox 2 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME2) != 0U) - { - freelevel++; - } - } - - /* Return Tx Mailboxes free level */ - return freelevel; -} - -/** - * @brief Check if a transmission request is pending on the selected Tx - * Mailboxes. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailboxes List of Tx Mailboxes to check. - * This parameter can be any combination of @arg CAN_Tx_Mailboxes. - * @retval Status - * - 0 : No pending transmission request on any selected Tx Mailboxes. - * - 1 : Pending transmission request on at least one of the selected - * Tx Mailbox. - */ -uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) -{ - uint32_t status = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check pending transmission request on the selected Tx Mailboxes */ - if ((hcan->Instance->TSR & (TxMailboxes << CAN_TSR_TME0_Pos)) != (TxMailboxes << CAN_TSR_TME0_Pos)) - { - status = 1U; - } - } - - /* Return status */ - return status; -} - -/** - * @brief Return timestamp of Tx message sent, if time triggered communication - mode is enabled. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailbox Tx Mailbox where the timestamp of message sent will be - * read. - * This parameter can be one value of @arg CAN_Tx_Mailboxes. - * @retval Timestamp of message sent from Tx Mailbox. - */ -uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox) -{ - uint32_t timestamp = 0U; - uint32_t transmitmailbox; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX(TxMailbox)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Select the Tx mailbox */ - transmitmailbox = POSITION_VAL(TxMailbox); - - /* Get timestamp */ - timestamp = (hcan->Instance->sTxMailBox[transmitmailbox].TDTR & CAN_TDT0R_TIME) >> CAN_TDT0R_TIME_Pos; - } - - /* Return the timestamp */ - return timestamp; -} - -/** - * @brief Get an CAN frame from the Rx FIFO zone into the message RAM. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param RxFifo Fifo number of the received message to be read. - * This parameter can be a value of @arg CAN_receive_FIFO_number. - * @param pHeader pointer to a CAN_RxHeaderTypeDef structure where the header - * of the Rx frame will be stored. - * @param aData array where the payload of the Rx frame will be stored. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - assert_param(IS_CAN_RX_FIFO(RxFifo)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check the Rx FIFO */ - if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ - { - /* Check that the Rx FIFO 0 is not empty */ - if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) == 0U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - else /* Rx element is assigned to Rx FIFO 1 */ - { - /* Check that the Rx FIFO 1 is not empty */ - if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) == 0U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - - /* Get the header */ - pHeader->IDE = CAN_RI0R_IDE & hcan->Instance->sFIFOMailBox[RxFifo].RIR; - if (pHeader->IDE == CAN_ID_STD) - { - pHeader->StdId = (CAN_RI0R_STID & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_TI0R_STID_Pos; - } - else - { - pHeader->ExtId = ((CAN_RI0R_EXID | CAN_RI0R_STID) & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_RI0R_EXID_Pos; - } - pHeader->RTR = (CAN_RI0R_RTR & hcan->Instance->sFIFOMailBox[RxFifo].RIR); - pHeader->DLC = (CAN_RDT0R_DLC & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_DLC_Pos; - pHeader->FilterMatchIndex = (CAN_RDT0R_FMI & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_FMI_Pos; - pHeader->Timestamp = (CAN_RDT0R_TIME & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_TIME_Pos; - - /* Get the data */ - aData[0] = (uint8_t)((CAN_RDL0R_DATA0 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA0_Pos); - aData[1] = (uint8_t)((CAN_RDL0R_DATA1 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA1_Pos); - aData[2] = (uint8_t)((CAN_RDL0R_DATA2 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA2_Pos); - aData[3] = (uint8_t)((CAN_RDL0R_DATA3 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA3_Pos); - aData[4] = (uint8_t)((CAN_RDH0R_DATA4 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA4_Pos); - aData[5] = (uint8_t)((CAN_RDH0R_DATA5 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA5_Pos); - aData[6] = (uint8_t)((CAN_RDH0R_DATA6 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA6_Pos); - aData[7] = (uint8_t)((CAN_RDH0R_DATA7 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA7_Pos); - - /* Release the FIFO */ - if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ - { - /* Release RX FIFO 0 */ - SET_BIT(hcan->Instance->RF0R, CAN_RF0R_RFOM0); - } - else /* Rx element is assigned to Rx FIFO 1 */ - { - /* Release RX FIFO 1 */ - SET_BIT(hcan->Instance->RF1R, CAN_RF1R_RFOM1); - } - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Return Rx FIFO fill level. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param RxFifo Rx FIFO. - * This parameter can be a value of @arg CAN_receive_FIFO_number. - * @retval Number of messages available in Rx FIFO. - */ -uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo) -{ - uint32_t filllevel = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_RX_FIFO(RxFifo)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - if (RxFifo == CAN_RX_FIFO0) - { - filllevel = hcan->Instance->RF0R & CAN_RF0R_FMP0; - } - else /* RxFifo == CAN_RX_FIFO1 */ - { - filllevel = hcan->Instance->RF1R & CAN_RF1R_FMP1; - } - } - - /* Return Rx FIFO fill level */ - return filllevel; -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group4 Interrupts management - * @brief Interrupts management - * -@verbatim - ============================================================================== - ##### Interrupts management ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_ActivateNotification : Enable interrupts - (+) HAL_CAN_DeactivateNotification : Disable interrupts - (+) HAL_CAN_IRQHandler : Handles CAN interrupt request - -@endverbatim - * @{ - */ - -/** - * @brief Enable interrupts. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param ActiveITs indicates which interrupts will be enabled. - * This parameter can be any combination of @arg CAN_Interrupts. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_IT(ActiveITs)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Enable the selected interrupts */ - __HAL_CAN_ENABLE_IT(hcan, ActiveITs); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Disable interrupts. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param InactiveITs indicates which interrupts will be disabled. - * This parameter can be any combination of @arg CAN_Interrupts. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_IT(InactiveITs)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Disable the selected interrupts */ - __HAL_CAN_DISABLE_IT(hcan, InactiveITs); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Handles CAN interrupt request - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan) -{ - uint32_t errorcode = HAL_CAN_ERROR_NONE; - uint32_t interrupts = READ_REG(hcan->Instance->IER); - uint32_t msrflags = READ_REG(hcan->Instance->MSR); - uint32_t tsrflags = READ_REG(hcan->Instance->TSR); - uint32_t rf0rflags = READ_REG(hcan->Instance->RF0R); - uint32_t rf1rflags = READ_REG(hcan->Instance->RF1R); - uint32_t esrflags = READ_REG(hcan->Instance->ESR); - - /* Transmit Mailbox empty interrupt management *****************************/ - if ((interrupts & CAN_IT_TX_MAILBOX_EMPTY) != 0U) - { - /* Transmit Mailbox 0 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP0) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK0,ALST0,TERR0 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP0); - - if ((tsrflags & CAN_TSR_TXOK0) != 0U) - { - /* Transmission Mailbox 0 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox0CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox0CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST0) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST0; - } - else if ((tsrflags & CAN_TSR_TERR0) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR0; - } - else - { - /* Transmission Mailbox 0 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox0AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox0AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - - /* Transmit Mailbox 1 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP1) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK1,ALST1,TERR1 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP1); - - if ((tsrflags & CAN_TSR_TXOK1) != 0U) - { - /* Transmission Mailbox 1 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox1CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox1CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST1) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST1; - } - else if ((tsrflags & CAN_TSR_TERR1) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR1; - } - else - { - /* Transmission Mailbox 1 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox1AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox1AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - - /* Transmit Mailbox 2 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP2) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK2,ALST2,TERR2 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP2); - - if ((tsrflags & CAN_TSR_TXOK2) != 0U) - { - /* Transmission Mailbox 2 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox2CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox2CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST2) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST2; - } - else if ((tsrflags & CAN_TSR_TERR2) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR2; - } - else - { - /* Transmission Mailbox 2 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox2AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox2AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - } - - /* Receive FIFO 0 overrun interrupt management *****************************/ - if ((interrupts & CAN_IT_RX_FIFO0_OVERRUN) != 0U) - { - if ((rf0rflags & CAN_RF0R_FOVR0) != 0U) - { - /* Set CAN error code to Rx Fifo 0 overrun error */ - errorcode |= HAL_CAN_ERROR_RX_FOV0; - - /* Clear FIFO0 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); - } - } - - /* Receive FIFO 0 full interrupt management ********************************/ - if ((interrupts & CAN_IT_RX_FIFO0_FULL) != 0U) - { - if ((rf0rflags & CAN_RF0R_FULL0) != 0U) - { - /* Clear FIFO 0 full Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF0); - - /* Receive FIFO 0 full Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo0FullCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo0FullCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 0 message pending interrupt management *********************/ - if ((interrupts & CAN_IT_RX_FIFO0_MSG_PENDING) != 0U) - { - /* Check if message is still pending */ - if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) != 0U) - { - /* Receive FIFO 0 message pending Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo0MsgPendingCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo0MsgPendingCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 1 overrun interrupt management *****************************/ - if ((interrupts & CAN_IT_RX_FIFO1_OVERRUN) != 0U) - { - if ((rf1rflags & CAN_RF1R_FOVR1) != 0U) - { - /* Set CAN error code to Rx Fifo 1 overrun error */ - errorcode |= HAL_CAN_ERROR_RX_FOV1; - - /* Clear FIFO1 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); - } - } - - /* Receive FIFO 1 full interrupt management ********************************/ - if ((interrupts & CAN_IT_RX_FIFO1_FULL) != 0U) - { - if ((rf1rflags & CAN_RF1R_FULL1) != 0U) - { - /* Clear FIFO 1 full Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF1); - - /* Receive FIFO 1 full Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo1FullCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo1FullCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 1 message pending interrupt management *********************/ - if ((interrupts & CAN_IT_RX_FIFO1_MSG_PENDING) != 0U) - { - /* Check if message is still pending */ - if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) != 0U) - { - /* Receive FIFO 1 message pending Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo1MsgPendingCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo1MsgPendingCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Sleep interrupt management *********************************************/ - if ((interrupts & CAN_IT_SLEEP_ACK) != 0U) - { - if ((msrflags & CAN_MSR_SLAKI) != 0U) - { - /* Clear Sleep interrupt Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_SLAKI); - - /* Sleep Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->SleepCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_SleepCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* WakeUp interrupt management *********************************************/ - if ((interrupts & CAN_IT_WAKEUP) != 0U) - { - if ((msrflags & CAN_MSR_WKUI) != 0U) - { - /* Clear WakeUp Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_WKU); - - /* WakeUp Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->WakeUpFromRxMsgCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_WakeUpFromRxMsgCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Error interrupts management *********************************************/ - if ((interrupts & CAN_IT_ERROR) != 0U) - { - if ((msrflags & CAN_MSR_ERRI) != 0U) - { - /* Check Error Warning Flag */ - if (((interrupts & CAN_IT_ERROR_WARNING) != 0U) && - ((esrflags & CAN_ESR_EWGF) != 0U)) - { - /* Set CAN error code to Error Warning */ - errorcode |= HAL_CAN_ERROR_EWG; - - /* No need for clear of Error Warning Flag as read-only */ - } - - /* Check Error Passive Flag */ - if (((interrupts & CAN_IT_ERROR_PASSIVE) != 0U) && - ((esrflags & CAN_ESR_EPVF) != 0U)) - { - /* Set CAN error code to Error Passive */ - errorcode |= HAL_CAN_ERROR_EPV; - - /* No need for clear of Error Passive Flag as read-only */ - } - - /* Check Bus-off Flag */ - if (((interrupts & CAN_IT_BUSOFF) != 0U) && - ((esrflags & CAN_ESR_BOFF) != 0U)) - { - /* Set CAN error code to Bus-Off */ - errorcode |= HAL_CAN_ERROR_BOF; - - /* No need for clear of Error Bus-Off as read-only */ - } - - /* Check Last Error Code Flag */ - if (((interrupts & CAN_IT_LAST_ERROR_CODE) != 0U) && - ((esrflags & CAN_ESR_LEC) != 0U)) - { - switch (esrflags & CAN_ESR_LEC) - { - case (CAN_ESR_LEC_0): - /* Set CAN error code to Stuff error */ - errorcode |= HAL_CAN_ERROR_STF; - break; - case (CAN_ESR_LEC_1): - /* Set CAN error code to Form error */ - errorcode |= HAL_CAN_ERROR_FOR; - break; - case (CAN_ESR_LEC_1 | CAN_ESR_LEC_0): - /* Set CAN error code to Acknowledgement error */ - errorcode |= HAL_CAN_ERROR_ACK; - break; - case (CAN_ESR_LEC_2): - /* Set CAN error code to Bit recessive error */ - errorcode |= HAL_CAN_ERROR_BR; - break; - case (CAN_ESR_LEC_2 | CAN_ESR_LEC_0): - /* Set CAN error code to Bit Dominant error */ - errorcode |= HAL_CAN_ERROR_BD; - break; - case (CAN_ESR_LEC_2 | CAN_ESR_LEC_1): - /* Set CAN error code to CRC error */ - errorcode |= HAL_CAN_ERROR_CRC; - break; - default: - break; - } - - /* Clear Last error code Flag */ - CLEAR_BIT(hcan->Instance->ESR, CAN_ESR_LEC); - } - } - - /* Clear ERRI Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_ERRI); - } - - /* Call the Error call Back in case of Errors */ - if (errorcode != HAL_CAN_ERROR_NONE) - { - /* Update error code in handle */ - hcan->ErrorCode |= errorcode; - - /* Call Error callback function */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->ErrorCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_ErrorCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group5 Callback functions - * @brief CAN Callback functions - * -@verbatim - ============================================================================== - ##### Callback functions ##### - ============================================================================== - [..] - This subsection provides the following callback functions: - (+) HAL_CAN_TxMailbox0CompleteCallback - (+) HAL_CAN_TxMailbox1CompleteCallback - (+) HAL_CAN_TxMailbox2CompleteCallback - (+) HAL_CAN_TxMailbox0AbortCallback - (+) HAL_CAN_TxMailbox1AbortCallback - (+) HAL_CAN_TxMailbox2AbortCallback - (+) HAL_CAN_RxFifo0MsgPendingCallback - (+) HAL_CAN_RxFifo0FullCallback - (+) HAL_CAN_RxFifo1MsgPendingCallback - (+) HAL_CAN_RxFifo1FullCallback - (+) HAL_CAN_SleepCallback - (+) HAL_CAN_WakeUpFromRxMsgCallback - (+) HAL_CAN_ErrorCallback - -@endverbatim - * @{ - */ - -/** - * @brief Transmission Mailbox 0 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox0CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 1 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox1CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 2 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox2CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 0 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox0AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 1 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox1AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 2 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox2AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 0 message pending callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo0MsgPendingCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 0 full callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo0FullCallback could be implemented in the user - file - */ -} - -/** - * @brief Rx FIFO 1 message pending callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo1MsgPendingCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 1 full callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo1FullCallback could be implemented in the user - file - */ -} - -/** - * @brief Sleep callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_SleepCallback could be implemented in the user file - */ -} - -/** - * @brief WakeUp from Rx message callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_WakeUpFromRxMsgCallback could be implemented in the - user file - */ -} - -/** - * @brief Error CAN callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group6 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Error functions ##### - ============================================================================== - [..] - This subsection provides functions allowing to : - (+) HAL_CAN_GetState() : Return the CAN state. - (+) HAL_CAN_GetError() : Return the CAN error codes if any. - (+) HAL_CAN_ResetError(): Reset the CAN error codes if any. - -@endverbatim - * @{ - */ - -/** - * @brief Return the CAN state. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL state - */ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check sleep mode acknowledge flag */ - if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - /* Sleep mode is active */ - state = HAL_CAN_STATE_SLEEP_ACTIVE; - } - /* Check sleep mode request flag */ - else if ((hcan->Instance->MCR & CAN_MCR_SLEEP) != 0U) - { - /* Sleep mode request is pending */ - state = HAL_CAN_STATE_SLEEP_PENDING; - } - else - { - /* Neither sleep mode request nor sleep mode acknowledge */ - } - } - - /* Return CAN state */ - return state; -} - -/** - * @brief Return the CAN error code. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval CAN Error Code - */ -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) -{ - /* Return CAN error code */ - return hcan->ErrorCode; -} - -/** - * @brief Reset the CAN error code. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Reset CAN error code */ - hcan->ErrorCode = 0U; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - status = HAL_ERROR; - } - - /* Return the status */ - return status; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_CAN_MODULE_ENABLED */ - -/** - * @} - */ - -#endif /* CAN1 */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_can.c + * @author MCD Application Team + * @brief CAN HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Controller Area Network (CAN) peripheral: + * + Initialization and de-initialization functions + * + Configuration functions + * + Control functions + * + Interrupts management + * + Callbacks functions + * + Peripheral State and Error functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the CAN low level resources by implementing the + HAL_CAN_MspInit(): + (++) Enable the CAN interface clock using __HAL_RCC_CANx_CLK_ENABLE() + (++) Configure CAN pins + (+++) Enable the clock for the CAN GPIOs + (+++) Configure CAN pins as alternate function open-drain + (++) In case of using interrupts (e.g. HAL_CAN_ActivateNotification()) + (+++) Configure the CAN interrupt priority using + HAL_NVIC_SetPriority() + (+++) Enable the CAN IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In CAN IRQ handler, call HAL_CAN_IRQHandler() + + (#) Initialize the CAN peripheral using HAL_CAN_Init() function. This + function resorts to HAL_CAN_MspInit() for low-level initialization. + + (#) Configure the reception filters using the following configuration + functions: + (++) HAL_CAN_ConfigFilter() + + (#) Start the CAN module using HAL_CAN_Start() function. At this level + the node is active on the bus: it receive messages, and can send + messages. + + (#) To manage messages transmission, the following Tx control functions + can be used: + (++) HAL_CAN_AddTxMessage() to request transmission of a new + message. + (++) HAL_CAN_AbortTxRequest() to abort transmission of a pending + message. + (++) HAL_CAN_GetTxMailboxesFreeLevel() to get the number of free Tx + mailboxes. + (++) HAL_CAN_IsTxMessagePending() to check if a message is pending + in a Tx mailbox. + (++) HAL_CAN_GetTxTimestamp() to get the timestamp of Tx message + sent, if time triggered communication mode is enabled. + + (#) When a message is received into the CAN Rx FIFOs, it can be retrieved + using the HAL_CAN_GetRxMessage() function. The function + HAL_CAN_GetRxFifoFillLevel() allows to know how many Rx message are + stored in the Rx Fifo. + + (#) Calling the HAL_CAN_Stop() function stops the CAN module. + + (#) The deinitialization is achieved with HAL_CAN_DeInit() function. + + + *** Polling mode operation *** + ============================== + [..] + (#) Reception: + (++) Monitor reception of message using HAL_CAN_GetRxFifoFillLevel() + until at least one message is received. + (++) Then get the message using HAL_CAN_GetRxMessage(). + + (#) Transmission: + (++) Monitor the Tx mailboxes availability until at least one Tx + mailbox is free, using HAL_CAN_GetTxMailboxesFreeLevel(). + (++) Then request transmission of a message using + HAL_CAN_AddTxMessage(). + + + *** Interrupt mode operation *** + ================================ + [..] + (#) Notifications are activated using HAL_CAN_ActivateNotification() + function. Then, the process can be controlled through the + available user callbacks: HAL_CAN_xxxCallback(), using same APIs + HAL_CAN_GetRxMessage() and HAL_CAN_AddTxMessage(). + + (#) Notifications can be deactivated using + HAL_CAN_DeactivateNotification() function. + + (#) Special care should be taken for CAN_IT_RX_FIFO0_MSG_PENDING and + CAN_IT_RX_FIFO1_MSG_PENDING notifications. These notifications trig + the callbacks HAL_CAN_RxFIFO0MsgPendingCallback() and + HAL_CAN_RxFIFO1MsgPendingCallback(). User has two possible options + here. + (++) Directly get the Rx message in the callback, using + HAL_CAN_GetRxMessage(). + (++) Or deactivate the notification in the callback without + getting the Rx message. The Rx message can then be got later + using HAL_CAN_GetRxMessage(). Once the Rx message have been + read, the notification can be activated again. + + + *** Sleep mode *** + ================== + [..] + (#) The CAN peripheral can be put in sleep mode (low power), using + HAL_CAN_RequestSleep(). The sleep mode will be entered as soon as the + current CAN activity (transmission or reception of a CAN frame) will + be completed. + + (#) A notification can be activated to be informed when the sleep mode + will be entered. + + (#) It can be checked if the sleep mode is entered using + HAL_CAN_IsSleepActive(). + Note that the CAN state (accessible from the API HAL_CAN_GetState()) + is HAL_CAN_STATE_SLEEP_PENDING as soon as the sleep mode request is + submitted (the sleep mode is not yet entered), and become + HAL_CAN_STATE_SLEEP_ACTIVE when the sleep mode is effective. + + (#) The wake-up from sleep mode can be triggered by two ways: + (++) Using HAL_CAN_WakeUp(). When returning from this function, + the sleep mode is exited (if return status is HAL_OK). + (++) When a start of Rx CAN frame is detected by the CAN peripheral, + if automatic wake up mode is enabled. + + *** Callback registration *** + ============================================= + + The compilation define USE_HAL_CAN_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Function HAL_CAN_RegisterCallback() to register an interrupt callback. + + Function HAL_CAN_RegisterCallback() allows to register following callbacks: + (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. + (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. + (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. + (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. + (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. + (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. + (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. + (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. + (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. + (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. + (+) SleepCallback : Sleep Callback. + (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. + (+) ErrorCallback : Error Callback. + (+) MspInitCallback : CAN MspInit. + (+) MspDeInitCallback : CAN MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_CAN_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_CAN_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. + (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. + (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. + (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. + (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. + (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. + (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. + (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. + (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. + (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. + (+) SleepCallback : Sleep Callback. + (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. + (+) ErrorCallback : Error Callback. + (+) MspInitCallback : CAN MspInit. + (+) MspDeInitCallback : CAN MspDeInit. + + By default, after the HAL_CAN_Init() and when the state is HAL_CAN_STATE_RESET, + all callbacks are set to the corresponding weak functions: + example HAL_CAN_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the HAL_CAN_Init()/ HAL_CAN_DeInit() only when + these callbacks are null (not registered beforehand). + if not, MspInit or MspDeInit are not null, the HAL_CAN_Init()/ HAL_CAN_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in HAL_CAN_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_CAN_STATE_READY or HAL_CAN_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_CAN_RegisterCallback() before calling HAL_CAN_DeInit() + or HAL_CAN_Init() function. + + When The compilation define USE_HAL_CAN_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined(CAN1) + +/** @defgroup CAN CAN + * @brief CAN driver modules + * @{ + */ + +#ifdef HAL_CAN_MODULE_ENABLED + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #error "The CAN driver cannot be used with its legacy, Please enable only one CAN module at once" +#endif + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup CAN_Private_Constants CAN Private Constants + * @{ + */ +#define CAN_TIMEOUT_VALUE 10U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup CAN_Exported_Functions CAN Exported Functions + * @{ + */ + +/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_Init : Initialize and configure the CAN. + (+) HAL_CAN_DeInit : De-initialize the CAN. + (+) HAL_CAN_MspInit : Initialize the CAN MSP. + (+) HAL_CAN_MspDeInit : DeInitialize the CAN MSP. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + /* Check CAN handle */ + if (hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TimeTriggeredMode)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoBusOff)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoWakeUp)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoRetransmission)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ReceiveFifoLocked)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TransmitFifoPriority)); + assert_param(IS_CAN_MODE(hcan->Init.Mode)); + assert_param(IS_CAN_SJW(hcan->Init.SyncJumpWidth)); + assert_param(IS_CAN_BS1(hcan->Init.TimeSeg1)); + assert_param(IS_CAN_BS2(hcan->Init.TimeSeg2)); + assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + if (hcan->State == HAL_CAN_STATE_RESET) + { + /* Reset callbacks to legacy functions */ + hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; /* Legacy weak RxFifo0MsgPendingCallback */ + hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; /* Legacy weak RxFifo0FullCallback */ + hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; /* Legacy weak RxFifo1MsgPendingCallback */ + hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; /* Legacy weak RxFifo1FullCallback */ + hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; /* Legacy weak TxMailbox0CompleteCallback */ + hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; /* Legacy weak TxMailbox1CompleteCallback */ + hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; /* Legacy weak TxMailbox2CompleteCallback */ + hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; /* Legacy weak TxMailbox0AbortCallback */ + hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; /* Legacy weak TxMailbox1AbortCallback */ + hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; /* Legacy weak TxMailbox2AbortCallback */ + hcan->SleepCallback = HAL_CAN_SleepCallback; /* Legacy weak SleepCallback */ + hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; /* Legacy weak WakeUpFromRxMsgCallback */ + hcan->ErrorCallback = HAL_CAN_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hcan->MspInitCallback == NULL) + { + hcan->MspInitCallback = HAL_CAN_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware: CLOCK, NVIC */ + hcan->MspInitCallback(hcan); + } + +#else + if (hcan->State == HAL_CAN_STATE_RESET) + { + /* Init the low level hardware: CLOCK, NVIC */ + HAL_CAN_MspInit(hcan); + } +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ + + /* Request initialisation */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait initialisation acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) + { + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Exit from sleep mode */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check Sleep mode leave acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Set the time triggered communication mode */ + if (hcan->Init.TimeTriggeredMode == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); + } + + /* Set the automatic bus-off management */ + if (hcan->Init.AutoBusOff == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); + } + + /* Set the automatic wake-up mode */ + if (hcan->Init.AutoWakeUp == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); + } + + /* Set the automatic retransmission */ + if (hcan->Init.AutoRetransmission == ENABLE) + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_NART); + } + else + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_NART); + } + + /* Set the receive FIFO locked mode */ + if (hcan->Init.ReceiveFifoLocked == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); + } + + /* Set the transmit FIFO priority */ + if (hcan->Init.TransmitFifoPriority == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); + } + + /* Set the bit timing register */ + WRITE_REG(hcan->Instance->BTR, (uint32_t)(hcan->Init.Mode | + hcan->Init.SyncJumpWidth | + hcan->Init.TimeSeg1 | + hcan->Init.TimeSeg2 | + (hcan->Init.Prescaler - 1U))); + + /* Initialize the error code */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Initialize the CAN state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Deinitializes the CAN peripheral registers to their default + * reset values. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan) +{ + /* Check CAN handle */ + if (hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + + /* Stop the CAN module */ + (void)HAL_CAN_Stop(hcan); + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + if (hcan->MspDeInitCallback == NULL) + { + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: CLOCK, NVIC */ + hcan->MspDeInitCallback(hcan); + +#else + /* DeInit the low level hardware: CLOCK, NVIC */ + HAL_CAN_MspDeInit(hcan); +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ + + /* Reset the CAN peripheral */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_RESET); + + /* Reset the CAN ErrorCode */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_RESET; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspDeInit could be implemented in the user file + */ +} + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +/** + * @brief Register a CAN CallBack. + * To be used instead of the weak predefined callback + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for CAN module + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID + * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID + * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID + * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID + * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID + * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + if (hcan->State == HAL_CAN_STATE_READY) + { + switch (CallbackID) + { + case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : + hcan->TxMailbox0CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : + hcan->TxMailbox1CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : + hcan->TxMailbox2CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : + hcan->TxMailbox0AbortCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : + hcan->TxMailbox1AbortCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : + hcan->TxMailbox2AbortCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : + hcan->RxFifo0MsgPendingCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO0_FULL_CB_ID : + hcan->RxFifo0FullCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : + hcan->RxFifo1MsgPendingCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO1_FULL_CB_ID : + hcan->RxFifo1FullCallback = pCallback; + break; + + case HAL_CAN_SLEEP_CB_ID : + hcan->SleepCallback = pCallback; + break; + + case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : + hcan->WakeUpFromRxMsgCallback = pCallback; + break; + + case HAL_CAN_ERROR_CB_ID : + hcan->ErrorCallback = pCallback; + break; + + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = pCallback; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcan->State == HAL_CAN_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = pCallback; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Unregister a CAN CallBack. + * CAN callback is redirected to the weak predefined callback + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for CAN module + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID + * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID + * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID + * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID + * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID + * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (hcan->State == HAL_CAN_STATE_READY) + { + switch (CallbackID) + { + case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : + hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : + hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : + hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : + hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; + break; + + case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : + hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; + break; + + case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : + hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; + break; + + case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : + hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; + break; + + case HAL_CAN_RX_FIFO0_FULL_CB_ID : + hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; + break; + + case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : + hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; + break; + + case HAL_CAN_RX_FIFO1_FULL_CB_ID : + hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; + break; + + case HAL_CAN_SLEEP_CB_ID : + hcan->SleepCallback = HAL_CAN_SleepCallback; + break; + + case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : + hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; + break; + + case HAL_CAN_ERROR_CB_ID : + hcan->ErrorCallback = HAL_CAN_ErrorCallback; + break; + + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = HAL_CAN_MspInit; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcan->State == HAL_CAN_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = HAL_CAN_MspInit; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group2 Configuration functions + * @brief Configuration functions. + * +@verbatim + ============================================================================== + ##### Configuration functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_ConfigFilter : Configure the CAN reception filters + +@endverbatim + * @{ + */ + +/** + * @brief Configures the CAN reception filter according to the specified + * parameters in the CAN_FilterInitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param sFilterConfig pointer to a CAN_FilterTypeDef structure that + * contains the filter configuration information. + * @retval None + */ +HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig) +{ + uint32_t filternbrbitpos; + CAN_TypeDef *can_ip = hcan->Instance; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check the parameters */ + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdHigh)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdLow)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdHigh)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdLow)); + assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); + assert_param(IS_CAN_FILTER_ACTIVATION(sFilterConfig->FilterActivation)); + +#if defined(CAN3) + /* Check the CAN instance */ + if (hcan->Instance == CAN3) + { + /* CAN3 is single instance with 14 dedicated filters banks */ + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); + } + else + { + /* CAN1 and CAN2 are dual instances with 28 common filters banks */ + /* Select master instance to access the filter banks */ + can_ip = CAN1; + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); + } +#elif defined(CAN2) + /* CAN1 and CAN2 are dual instances with 28 common filters banks */ + /* Select master instance to access the filter banks */ + can_ip = CAN1; + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); +#else + /* CAN1 is single instance with 14 dedicated filters banks */ + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); +#endif + + /* Initialisation mode for the filter */ + SET_BIT(can_ip->FMR, CAN_FMR_FINIT); + +#if defined(CAN3) + /* Check the CAN instance */ + if (can_ip == CAN1) + { + /* Select the start filter number of CAN2 slave instance */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); + SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); + } + +#elif defined(CAN2) + /* Select the start filter number of CAN2 slave instance */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); + SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); + +#endif + /* Convert filter number into bit position */ + filternbrbitpos = (uint32_t)1 << (sFilterConfig->FilterBank & 0x1FU); + + /* Filter Deactivation */ + CLEAR_BIT(can_ip->FA1R, filternbrbitpos); + + /* Filter Scale */ + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) + { + /* 16-bit scale for the filter */ + CLEAR_BIT(can_ip->FS1R, filternbrbitpos); + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); + } + + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) + { + /* 32-bit scale for the filter */ + SET_BIT(can_ip->FS1R, filternbrbitpos); + + /* 32-bit identifier or First 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + + /* 32-bit mask or Second 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); + } + + /* Filter Mode */ + if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) + { + /* Id/Mask mode for the filter*/ + CLEAR_BIT(can_ip->FM1R, filternbrbitpos); + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /* Identifier list mode for the filter*/ + SET_BIT(can_ip->FM1R, filternbrbitpos); + } + + /* Filter FIFO assignment */ + if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CLEAR_BIT(can_ip->FFA1R, filternbrbitpos); + } + else + { + /* FIFO 1 assignation for the filter */ + SET_BIT(can_ip->FFA1R, filternbrbitpos); + } + + /* Filter activation */ + if (sFilterConfig->FilterActivation == CAN_FILTER_ENABLE) + { + SET_BIT(can_ip->FA1R, filternbrbitpos); + } + + /* Leave the initialisation mode for the filter */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_FINIT); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group3 Control functions + * @brief Control functions + * +@verbatim + ============================================================================== + ##### Control functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_Start : Start the CAN module + (+) HAL_CAN_Stop : Stop the CAN module + (+) HAL_CAN_RequestSleep : Request sleep mode entry. + (+) HAL_CAN_WakeUp : Wake up from sleep mode. + (+) HAL_CAN_IsSleepActive : Check is sleep mode is active. + (+) HAL_CAN_AddTxMessage : Add a message to the Tx mailboxes + and activate the corresponding + transmission request + (+) HAL_CAN_AbortTxRequest : Abort transmission request + (+) HAL_CAN_GetTxMailboxesFreeLevel : Return Tx mailboxes free level + (+) HAL_CAN_IsTxMessagePending : Check if a transmission request is + pending on the selected Tx mailbox + (+) HAL_CAN_GetRxMessage : Get a CAN frame from the Rx FIFO + (+) HAL_CAN_GetRxFifoFillLevel : Return Rx FIFO fill level + +@endverbatim + * @{ + */ + +/** + * @brief Start the CAN module. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + if (hcan->State == HAL_CAN_STATE_READY) + { + /* Change CAN peripheral state */ + hcan->State = HAL_CAN_STATE_LISTENING; + + /* Request leave initialisation */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Reset the CAN ErrorCode */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_READY; + + return HAL_ERROR; + } +} + +/** + * @brief Stop the CAN module and enable access to configuration registers. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + if (hcan->State == HAL_CAN_STATE_LISTENING) + { + /* Request initialisation */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Exit from sleep mode */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Change CAN peripheral state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_STARTED; + + return HAL_ERROR; + } +} + +/** + * @brief Request the sleep mode (low power) entry. + * When returning from this function, Sleep mode will be entered + * as soon as the current CAN activity (transmission or reception + * of a CAN frame) has been completed. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Request Sleep mode */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + /* Return function status */ + return HAL_ERROR; + } +} + +/** + * @brief Wake up from sleep mode. + * When returning with HAL_OK status from this function, Sleep mode + * is exited. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan) +{ + __IO uint32_t count = 0; + uint32_t timeout = 1000000U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Wake up request */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Wait sleep mode is exited */ + do + { + /* Increment counter */ + count++; + + /* Check if timeout is reached */ + if (count > timeout) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + return HAL_ERROR; + } + } + while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Check is sleep mode is active. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval Status + * - 0 : Sleep mode is not active. + * - 1 : Sleep mode is active. + */ +uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan) +{ + uint32_t status = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Sleep mode */ + if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + status = 1U; + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Add a message to the first free Tx mailbox and activate the + * corresponding transmission request. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param pHeader pointer to a CAN_TxHeaderTypeDef structure. + * @param aData array containing the payload of the Tx frame. + * @param pTxMailbox pointer to a variable where the function will return + * the TxMailbox used to store the Tx message. + * This parameter can be a value of @arg CAN_Tx_Mailboxes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox) +{ + uint32_t transmitmailbox; + HAL_CAN_StateTypeDef state = hcan->State; + uint32_t tsr = READ_REG(hcan->Instance->TSR); + + /* Check the parameters */ + assert_param(IS_CAN_IDTYPE(pHeader->IDE)); + assert_param(IS_CAN_RTR(pHeader->RTR)); + assert_param(IS_CAN_DLC(pHeader->DLC)); + if (pHeader->IDE == CAN_ID_STD) + { + assert_param(IS_CAN_STDID(pHeader->StdId)); + } + else + { + assert_param(IS_CAN_EXTID(pHeader->ExtId)); + } + assert_param(IS_FUNCTIONAL_STATE(pHeader->TransmitGlobalTime)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check that all the Tx mailboxes are not full */ + if (((tsr & CAN_TSR_TME0) != 0U) || + ((tsr & CAN_TSR_TME1) != 0U) || + ((tsr & CAN_TSR_TME2) != 0U)) + { + /* Select an empty transmit mailbox */ + transmitmailbox = (tsr & CAN_TSR_CODE) >> CAN_TSR_CODE_Pos; + + /* Check transmit mailbox value */ + if (transmitmailbox > 2U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INTERNAL; + + return HAL_ERROR; + } + + /* Store the Tx mailbox */ + *pTxMailbox = (uint32_t)1 << transmitmailbox; + + /* Set up the Id */ + if (pHeader->IDE == CAN_ID_STD) + { + hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->StdId << CAN_TI0R_STID_Pos) | + pHeader->RTR); + } + else + { + hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->ExtId << CAN_TI0R_EXID_Pos) | + pHeader->IDE | + pHeader->RTR); + } + + /* Set up the DLC */ + hcan->Instance->sTxMailBox[transmitmailbox].TDTR = (pHeader->DLC); + + /* Set up the Transmit Global Time mode */ + if (pHeader->TransmitGlobalTime == ENABLE) + { + SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TDTR, CAN_TDT0R_TGT); + } + + /* Set up the data field */ + WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDHR, + ((uint32_t)aData[7] << CAN_TDH0R_DATA7_Pos) | + ((uint32_t)aData[6] << CAN_TDH0R_DATA6_Pos) | + ((uint32_t)aData[5] << CAN_TDH0R_DATA5_Pos) | + ((uint32_t)aData[4] << CAN_TDH0R_DATA4_Pos)); + WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDLR, + ((uint32_t)aData[3] << CAN_TDL0R_DATA3_Pos) | + ((uint32_t)aData[2] << CAN_TDL0R_DATA2_Pos) | + ((uint32_t)aData[1] << CAN_TDL0R_DATA1_Pos) | + ((uint32_t)aData[0] << CAN_TDL0R_DATA0_Pos)); + + /* Request transmission */ + SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TIR, CAN_TI0R_TXRQ); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Abort transmission requests + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailboxes List of the Tx Mailboxes to abort. + * This parameter can be any combination of @arg CAN_Tx_Mailboxes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Tx Mailbox 0 */ + if ((TxMailboxes & CAN_TX_MAILBOX0) != 0U) + { + /* Add cancellation request for Tx Mailbox 0 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ0); + } + + /* Check Tx Mailbox 1 */ + if ((TxMailboxes & CAN_TX_MAILBOX1) != 0U) + { + /* Add cancellation request for Tx Mailbox 1 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ1); + } + + /* Check Tx Mailbox 2 */ + if ((TxMailboxes & CAN_TX_MAILBOX2) != 0U) + { + /* Add cancellation request for Tx Mailbox 2 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ2); + } + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Return Tx Mailboxes free level: number of free Tx Mailboxes. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval Number of free Tx Mailboxes. + */ +uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan) +{ + uint32_t freelevel = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Tx Mailbox 0 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME0) != 0U) + { + freelevel++; + } + + /* Check Tx Mailbox 1 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME1) != 0U) + { + freelevel++; + } + + /* Check Tx Mailbox 2 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME2) != 0U) + { + freelevel++; + } + } + + /* Return Tx Mailboxes free level */ + return freelevel; +} + +/** + * @brief Check if a transmission request is pending on the selected Tx + * Mailboxes. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailboxes List of Tx Mailboxes to check. + * This parameter can be any combination of @arg CAN_Tx_Mailboxes. + * @retval Status + * - 0 : No pending transmission request on any selected Tx Mailboxes. + * - 1 : Pending transmission request on at least one of the selected + * Tx Mailbox. + */ +uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) +{ + uint32_t status = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check pending transmission request on the selected Tx Mailboxes */ + if ((hcan->Instance->TSR & (TxMailboxes << CAN_TSR_TME0_Pos)) != (TxMailboxes << CAN_TSR_TME0_Pos)) + { + status = 1U; + } + } + + /* Return status */ + return status; +} + +/** + * @brief Return timestamp of Tx message sent, if time triggered communication + mode is enabled. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailbox Tx Mailbox where the timestamp of message sent will be + * read. + * This parameter can be one value of @arg CAN_Tx_Mailboxes. + * @retval Timestamp of message sent from Tx Mailbox. + */ +uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox) +{ + uint32_t timestamp = 0U; + uint32_t transmitmailbox; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX(TxMailbox)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Select the Tx mailbox */ + transmitmailbox = POSITION_VAL(TxMailbox); + + /* Get timestamp */ + timestamp = (hcan->Instance->sTxMailBox[transmitmailbox].TDTR & CAN_TDT0R_TIME) >> CAN_TDT0R_TIME_Pos; + } + + /* Return the timestamp */ + return timestamp; +} + +/** + * @brief Get an CAN frame from the Rx FIFO zone into the message RAM. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param RxFifo Fifo number of the received message to be read. + * This parameter can be a value of @arg CAN_receive_FIFO_number. + * @param pHeader pointer to a CAN_RxHeaderTypeDef structure where the header + * of the Rx frame will be stored. + * @param aData array where the payload of the Rx frame will be stored. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + assert_param(IS_CAN_RX_FIFO(RxFifo)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check the Rx FIFO */ + if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ + { + /* Check that the Rx FIFO 0 is not empty */ + if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) == 0U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + else /* Rx element is assigned to Rx FIFO 1 */ + { + /* Check that the Rx FIFO 1 is not empty */ + if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) == 0U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + + /* Get the header */ + pHeader->IDE = CAN_RI0R_IDE & hcan->Instance->sFIFOMailBox[RxFifo].RIR; + if (pHeader->IDE == CAN_ID_STD) + { + pHeader->StdId = (CAN_RI0R_STID & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_TI0R_STID_Pos; + } + else + { + pHeader->ExtId = ((CAN_RI0R_EXID | CAN_RI0R_STID) & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_RI0R_EXID_Pos; + } + pHeader->RTR = (CAN_RI0R_RTR & hcan->Instance->sFIFOMailBox[RxFifo].RIR); + pHeader->DLC = (CAN_RDT0R_DLC & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_DLC_Pos; + pHeader->FilterMatchIndex = (CAN_RDT0R_FMI & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_FMI_Pos; + pHeader->Timestamp = (CAN_RDT0R_TIME & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_TIME_Pos; + + /* Get the data */ + aData[0] = (uint8_t)((CAN_RDL0R_DATA0 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA0_Pos); + aData[1] = (uint8_t)((CAN_RDL0R_DATA1 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA1_Pos); + aData[2] = (uint8_t)((CAN_RDL0R_DATA2 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA2_Pos); + aData[3] = (uint8_t)((CAN_RDL0R_DATA3 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA3_Pos); + aData[4] = (uint8_t)((CAN_RDH0R_DATA4 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA4_Pos); + aData[5] = (uint8_t)((CAN_RDH0R_DATA5 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA5_Pos); + aData[6] = (uint8_t)((CAN_RDH0R_DATA6 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA6_Pos); + aData[7] = (uint8_t)((CAN_RDH0R_DATA7 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA7_Pos); + + /* Release the FIFO */ + if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ + { + /* Release RX FIFO 0 */ + SET_BIT(hcan->Instance->RF0R, CAN_RF0R_RFOM0); + } + else /* Rx element is assigned to Rx FIFO 1 */ + { + /* Release RX FIFO 1 */ + SET_BIT(hcan->Instance->RF1R, CAN_RF1R_RFOM1); + } + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Return Rx FIFO fill level. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param RxFifo Rx FIFO. + * This parameter can be a value of @arg CAN_receive_FIFO_number. + * @retval Number of messages available in Rx FIFO. + */ +uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo) +{ + uint32_t filllevel = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_RX_FIFO(RxFifo)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + if (RxFifo == CAN_RX_FIFO0) + { + filllevel = hcan->Instance->RF0R & CAN_RF0R_FMP0; + } + else /* RxFifo == CAN_RX_FIFO1 */ + { + filllevel = hcan->Instance->RF1R & CAN_RF1R_FMP1; + } + } + + /* Return Rx FIFO fill level */ + return filllevel; +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group4 Interrupts management + * @brief Interrupts management + * +@verbatim + ============================================================================== + ##### Interrupts management ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_ActivateNotification : Enable interrupts + (+) HAL_CAN_DeactivateNotification : Disable interrupts + (+) HAL_CAN_IRQHandler : Handles CAN interrupt request + +@endverbatim + * @{ + */ + +/** + * @brief Enable interrupts. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param ActiveITs indicates which interrupts will be enabled. + * This parameter can be any combination of @arg CAN_Interrupts. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_IT(ActiveITs)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Enable the selected interrupts */ + __HAL_CAN_ENABLE_IT(hcan, ActiveITs); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Disable interrupts. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param InactiveITs indicates which interrupts will be disabled. + * This parameter can be any combination of @arg CAN_Interrupts. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_IT(InactiveITs)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Disable the selected interrupts */ + __HAL_CAN_DISABLE_IT(hcan, InactiveITs); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Handles CAN interrupt request + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan) +{ + uint32_t errorcode = HAL_CAN_ERROR_NONE; + uint32_t interrupts = READ_REG(hcan->Instance->IER); + uint32_t msrflags = READ_REG(hcan->Instance->MSR); + uint32_t tsrflags = READ_REG(hcan->Instance->TSR); + uint32_t rf0rflags = READ_REG(hcan->Instance->RF0R); + uint32_t rf1rflags = READ_REG(hcan->Instance->RF1R); + uint32_t esrflags = READ_REG(hcan->Instance->ESR); + + /* Transmit Mailbox empty interrupt management *****************************/ + if ((interrupts & CAN_IT_TX_MAILBOX_EMPTY) != 0U) + { + /* Transmit Mailbox 0 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP0) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK0,ALST0,TERR0 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP0); + + if ((tsrflags & CAN_TSR_TXOK0) != 0U) + { + /* Transmission Mailbox 0 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox0CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox0CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST0) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST0; + } + else if ((tsrflags & CAN_TSR_TERR0) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR0; + } + else + { + /* Transmission Mailbox 0 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox0AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox0AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + + /* Transmit Mailbox 1 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP1) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK1,ALST1,TERR1 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP1); + + if ((tsrflags & CAN_TSR_TXOK1) != 0U) + { + /* Transmission Mailbox 1 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox1CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox1CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST1) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST1; + } + else if ((tsrflags & CAN_TSR_TERR1) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR1; + } + else + { + /* Transmission Mailbox 1 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox1AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox1AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + + /* Transmit Mailbox 2 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP2) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK2,ALST2,TERR2 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP2); + + if ((tsrflags & CAN_TSR_TXOK2) != 0U) + { + /* Transmission Mailbox 2 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox2CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox2CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST2) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST2; + } + else if ((tsrflags & CAN_TSR_TERR2) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR2; + } + else + { + /* Transmission Mailbox 2 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox2AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox2AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + } + + /* Receive FIFO 0 overrun interrupt management *****************************/ + if ((interrupts & CAN_IT_RX_FIFO0_OVERRUN) != 0U) + { + if ((rf0rflags & CAN_RF0R_FOVR0) != 0U) + { + /* Set CAN error code to Rx Fifo 0 overrun error */ + errorcode |= HAL_CAN_ERROR_RX_FOV0; + + /* Clear FIFO0 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); + } + } + + /* Receive FIFO 0 full interrupt management ********************************/ + if ((interrupts & CAN_IT_RX_FIFO0_FULL) != 0U) + { + if ((rf0rflags & CAN_RF0R_FULL0) != 0U) + { + /* Clear FIFO 0 full Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF0); + + /* Receive FIFO 0 full Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo0FullCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo0FullCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 0 message pending interrupt management *********************/ + if ((interrupts & CAN_IT_RX_FIFO0_MSG_PENDING) != 0U) + { + /* Check if message is still pending */ + if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) != 0U) + { + /* Receive FIFO 0 message pending Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo0MsgPendingCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo0MsgPendingCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 1 overrun interrupt management *****************************/ + if ((interrupts & CAN_IT_RX_FIFO1_OVERRUN) != 0U) + { + if ((rf1rflags & CAN_RF1R_FOVR1) != 0U) + { + /* Set CAN error code to Rx Fifo 1 overrun error */ + errorcode |= HAL_CAN_ERROR_RX_FOV1; + + /* Clear FIFO1 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); + } + } + + /* Receive FIFO 1 full interrupt management ********************************/ + if ((interrupts & CAN_IT_RX_FIFO1_FULL) != 0U) + { + if ((rf1rflags & CAN_RF1R_FULL1) != 0U) + { + /* Clear FIFO 1 full Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF1); + + /* Receive FIFO 1 full Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo1FullCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo1FullCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 1 message pending interrupt management *********************/ + if ((interrupts & CAN_IT_RX_FIFO1_MSG_PENDING) != 0U) + { + /* Check if message is still pending */ + if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) != 0U) + { + /* Receive FIFO 1 message pending Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo1MsgPendingCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo1MsgPendingCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Sleep interrupt management *********************************************/ + if ((interrupts & CAN_IT_SLEEP_ACK) != 0U) + { + if ((msrflags & CAN_MSR_SLAKI) != 0U) + { + /* Clear Sleep interrupt Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_SLAKI); + + /* Sleep Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->SleepCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_SleepCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* WakeUp interrupt management *********************************************/ + if ((interrupts & CAN_IT_WAKEUP) != 0U) + { + if ((msrflags & CAN_MSR_WKUI) != 0U) + { + /* Clear WakeUp Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_WKU); + + /* WakeUp Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->WakeUpFromRxMsgCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_WakeUpFromRxMsgCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Error interrupts management *********************************************/ + if ((interrupts & CAN_IT_ERROR) != 0U) + { + if ((msrflags & CAN_MSR_ERRI) != 0U) + { + /* Check Error Warning Flag */ + if (((interrupts & CAN_IT_ERROR_WARNING) != 0U) && + ((esrflags & CAN_ESR_EWGF) != 0U)) + { + /* Set CAN error code to Error Warning */ + errorcode |= HAL_CAN_ERROR_EWG; + + /* No need for clear of Error Warning Flag as read-only */ + } + + /* Check Error Passive Flag */ + if (((interrupts & CAN_IT_ERROR_PASSIVE) != 0U) && + ((esrflags & CAN_ESR_EPVF) != 0U)) + { + /* Set CAN error code to Error Passive */ + errorcode |= HAL_CAN_ERROR_EPV; + + /* No need for clear of Error Passive Flag as read-only */ + } + + /* Check Bus-off Flag */ + if (((interrupts & CAN_IT_BUSOFF) != 0U) && + ((esrflags & CAN_ESR_BOFF) != 0U)) + { + /* Set CAN error code to Bus-Off */ + errorcode |= HAL_CAN_ERROR_BOF; + + /* No need for clear of Error Bus-Off as read-only */ + } + + /* Check Last Error Code Flag */ + if (((interrupts & CAN_IT_LAST_ERROR_CODE) != 0U) && + ((esrflags & CAN_ESR_LEC) != 0U)) + { + switch (esrflags & CAN_ESR_LEC) + { + case (CAN_ESR_LEC_0): + /* Set CAN error code to Stuff error */ + errorcode |= HAL_CAN_ERROR_STF; + break; + case (CAN_ESR_LEC_1): + /* Set CAN error code to Form error */ + errorcode |= HAL_CAN_ERROR_FOR; + break; + case (CAN_ESR_LEC_1 | CAN_ESR_LEC_0): + /* Set CAN error code to Acknowledgement error */ + errorcode |= HAL_CAN_ERROR_ACK; + break; + case (CAN_ESR_LEC_2): + /* Set CAN error code to Bit recessive error */ + errorcode |= HAL_CAN_ERROR_BR; + break; + case (CAN_ESR_LEC_2 | CAN_ESR_LEC_0): + /* Set CAN error code to Bit Dominant error */ + errorcode |= HAL_CAN_ERROR_BD; + break; + case (CAN_ESR_LEC_2 | CAN_ESR_LEC_1): + /* Set CAN error code to CRC error */ + errorcode |= HAL_CAN_ERROR_CRC; + break; + default: + break; + } + + /* Clear Last error code Flag */ + CLEAR_BIT(hcan->Instance->ESR, CAN_ESR_LEC); + } + } + + /* Clear ERRI Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_ERRI); + } + + /* Call the Error call Back in case of Errors */ + if (errorcode != HAL_CAN_ERROR_NONE) + { + /* Update error code in handle */ + hcan->ErrorCode |= errorcode; + + /* Call Error callback function */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->ErrorCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_ErrorCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group5 Callback functions + * @brief CAN Callback functions + * +@verbatim + ============================================================================== + ##### Callback functions ##### + ============================================================================== + [..] + This subsection provides the following callback functions: + (+) HAL_CAN_TxMailbox0CompleteCallback + (+) HAL_CAN_TxMailbox1CompleteCallback + (+) HAL_CAN_TxMailbox2CompleteCallback + (+) HAL_CAN_TxMailbox0AbortCallback + (+) HAL_CAN_TxMailbox1AbortCallback + (+) HAL_CAN_TxMailbox2AbortCallback + (+) HAL_CAN_RxFifo0MsgPendingCallback + (+) HAL_CAN_RxFifo0FullCallback + (+) HAL_CAN_RxFifo1MsgPendingCallback + (+) HAL_CAN_RxFifo1FullCallback + (+) HAL_CAN_SleepCallback + (+) HAL_CAN_WakeUpFromRxMsgCallback + (+) HAL_CAN_ErrorCallback + +@endverbatim + * @{ + */ + +/** + * @brief Transmission Mailbox 0 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox0CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 1 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox1CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 2 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox2CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 0 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox0AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 1 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox1AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 2 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox2AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 0 message pending callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo0MsgPendingCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 0 full callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo0FullCallback could be implemented in the user + file + */ +} + +/** + * @brief Rx FIFO 1 message pending callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo1MsgPendingCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 1 full callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo1FullCallback could be implemented in the user + file + */ +} + +/** + * @brief Sleep callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_SleepCallback could be implemented in the user file + */ +} + +/** + * @brief WakeUp from Rx message callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_WakeUpFromRxMsgCallback could be implemented in the + user file + */ +} + +/** + * @brief Error CAN callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group6 Peripheral State and Error functions + * @brief CAN Peripheral State functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Error functions ##### + ============================================================================== + [..] + This subsection provides functions allowing to : + (+) HAL_CAN_GetState() : Return the CAN state. + (+) HAL_CAN_GetError() : Return the CAN error codes if any. + (+) HAL_CAN_ResetError(): Reset the CAN error codes if any. + +@endverbatim + * @{ + */ + +/** + * @brief Return the CAN state. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL state + */ +HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check sleep mode acknowledge flag */ + if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + /* Sleep mode is active */ + state = HAL_CAN_STATE_SLEEP_ACTIVE; + } + /* Check sleep mode request flag */ + else if ((hcan->Instance->MCR & CAN_MCR_SLEEP) != 0U) + { + /* Sleep mode request is pending */ + state = HAL_CAN_STATE_SLEEP_PENDING; + } + else + { + /* Neither sleep mode request nor sleep mode acknowledge */ + } + } + + /* Return CAN state */ + return state; +} + +/** + * @brief Return the CAN error code. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval CAN Error Code + */ +uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) +{ + /* Return CAN error code */ + return hcan->ErrorCode; +} + +/** + * @brief Reset the CAN error code. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Reset CAN error code */ + hcan->ErrorCode = 0U; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + status = HAL_ERROR; + } + + /* Return the status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_CAN_MODULE_ENABLED */ + +/** + * @} + */ + +#endif /* CAN1 */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c index 98515c5..5970852 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c @@ -1,502 +1,502 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cortex.c - * @author MCD Application Team - * @brief CORTEX HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the CORTEX: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - - [..] - *** How to configure Interrupts using CORTEX HAL driver *** - =========================================================== - [..] - This section provides functions allowing to configure the NVIC interrupts (IRQ). - The Cortex-M4 exceptions are managed by CMSIS functions. - - (#) Configure the NVIC Priority Grouping using HAL_NVIC_SetPriorityGrouping() - function according to the following table. - (#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority(). - (#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ(). - (#) please refer to programming manual for details in how to configure priority. - - -@- When the NVIC_PRIORITYGROUP_0 is selected, IRQ preemption is no more possible. - The pending IRQ priority will be managed only by the sub priority. - - -@- IRQ priority order (sorted by highest to lowest priority): - (+@) Lowest preemption priority - (+@) Lowest sub priority - (+@) Lowest hardware priority (IRQ number) - - [..] - *** How to configure Systick using CORTEX HAL driver *** - ======================================================== - [..] - Setup SysTick Timer for time base. - - (+) The HAL_SYSTICK_Config() function calls the SysTick_Config() function which - is a CMSIS function that: - (++) Configures the SysTick Reload register with value passed as function parameter. - (++) Configures the SysTick IRQ priority to the lowest value 0x0F. - (++) Resets the SysTick Counter register. - (++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK). - (++) Enables the SysTick Interrupt. - (++) Starts the SysTick Counter. - - (+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro - __HAL_CORTEX_SYSTICKCLK_CONFIG(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the - HAL_SYSTICK_Config() function call. The __HAL_CORTEX_SYSTICKCLK_CONFIG() macro is defined - inside the stm32f4xx_hal_cortex.h file. - - (+) You can change the SysTick IRQ priority by calling the - HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function - call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function. - - (+) To adjust the SysTick time base, use the following formula: - - Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s) - (++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function - (++) Reload Value should not exceed 0xFFFFFF - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup CORTEX CORTEX - * @brief CORTEX HAL module driver - * @{ - */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup CORTEX_Exported_Functions CORTEX Exported Functions - * @{ - */ - - -/** @defgroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides the CORTEX HAL driver functions allowing to configure Interrupts - Systick functionalities - -@endverbatim - * @{ - */ - - -/** - * @brief Sets the priority grouping field (preemption priority and subpriority) - * using the required unlock sequence. - * @param PriorityGroup The priority grouping bits length. - * This parameter can be one of the following values: - * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority - * 4 bits for subpriority - * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority - * 3 bits for subpriority - * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority - * 2 bits for subpriority - * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority - * 1 bits for subpriority - * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority - * 0 bits for subpriority - * @note When the NVIC_PriorityGroup_0 is selected, IRQ preemption is no more possible. - * The pending IRQ priority will be managed only by the subpriority. - * @retval None - */ -void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - /* Check the parameters */ - assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); - - /* Set the PRIGROUP[10:8] bits according to the PriorityGroup parameter value */ - NVIC_SetPriorityGrouping(PriorityGroup); -} - -/** - * @brief Sets the priority of an interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @param PreemptPriority The preemption priority for the IRQn channel. - * This parameter can be a value between 0 and 15 - * A lower priority value indicates a higher priority - * @param SubPriority the subpriority level for the IRQ channel. - * This parameter can be a value between 0 and 15 - * A lower priority value indicates a higher priority. - * @retval None - */ -void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t prioritygroup = 0x00U; - - /* Check the parameters */ - assert_param(IS_NVIC_SUB_PRIORITY(SubPriority)); - assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); - - prioritygroup = NVIC_GetPriorityGrouping(); - - NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); -} - -/** - * @brief Enables a device specific interrupt in the NVIC interrupt controller. - * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() - * function should be called before. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_EnableIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Enable interrupt */ - NVIC_EnableIRQ(IRQn); -} - -/** - * @brief Disables a device specific interrupt in the NVIC interrupt controller. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_DisableIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Disable interrupt */ - NVIC_DisableIRQ(IRQn); -} - -/** - * @brief Initiates a system reset request to reset the MCU. - * @retval None - */ -void HAL_NVIC_SystemReset(void) -{ - /* System Reset */ - NVIC_SystemReset(); -} - -/** - * @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer. - * Counter is in free running mode to generate periodic interrupts. - * @param TicksNumb Specifies the ticks Number of ticks between two interrupts. - * @retval status: - 0 Function succeeded. - * - 1 Function failed. - */ -uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb) -{ - return SysTick_Config(TicksNumb); -} -/** - * @} - */ - -/** @defgroup CORTEX_Exported_Functions_Group2 Peripheral Control functions - * @brief Cortex control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the CORTEX - (NVIC, SYSTICK, MPU) functionalities. - - -@endverbatim - * @{ - */ - -#if (__MPU_PRESENT == 1U) -/** - * @brief Disables the MPU - * @retval None - */ -void HAL_MPU_Disable(void) -{ - /* Make sure outstanding transfers are done */ - __DMB(); - - /* Disable fault exceptions */ - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; - - /* Disable the MPU and clear the control register*/ - MPU->CTRL = 0U; -} - -/** - * @brief Enable the MPU. - * @param MPU_Control Specifies the control mode of the MPU during hard fault, - * NMI, FAULTMASK and privileged access to the default memory - * This parameter can be one of the following values: - * @arg MPU_HFNMI_PRIVDEF_NONE - * @arg MPU_HARDFAULT_NMI - * @arg MPU_PRIVILEGED_DEFAULT - * @arg MPU_HFNMI_PRIVDEF - * @retval None - */ -void HAL_MPU_Enable(uint32_t MPU_Control) -{ - /* Enable the MPU */ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; - - /* Enable fault exceptions */ - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; - - /* Ensure MPU setting take effects */ - __DSB(); - __ISB(); -} - -/** - * @brief Initializes and configures the Region and the memory to be protected. - * @param MPU_Init Pointer to a MPU_Region_InitTypeDef structure that contains - * the initialization and configuration information. - * @retval None - */ -void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init) -{ - /* Check the parameters */ - assert_param(IS_MPU_REGION_NUMBER(MPU_Init->Number)); - assert_param(IS_MPU_REGION_ENABLE(MPU_Init->Enable)); - - /* Set the Region number */ - MPU->RNR = MPU_Init->Number; - - if ((MPU_Init->Enable) != RESET) - { - /* Check the parameters */ - assert_param(IS_MPU_INSTRUCTION_ACCESS(MPU_Init->DisableExec)); - assert_param(IS_MPU_REGION_PERMISSION_ATTRIBUTE(MPU_Init->AccessPermission)); - assert_param(IS_MPU_TEX_LEVEL(MPU_Init->TypeExtField)); - assert_param(IS_MPU_ACCESS_SHAREABLE(MPU_Init->IsShareable)); - assert_param(IS_MPU_ACCESS_CACHEABLE(MPU_Init->IsCacheable)); - assert_param(IS_MPU_ACCESS_BUFFERABLE(MPU_Init->IsBufferable)); - assert_param(IS_MPU_SUB_REGION_DISABLE(MPU_Init->SubRegionDisable)); - assert_param(IS_MPU_REGION_SIZE(MPU_Init->Size)); - - MPU->RBAR = MPU_Init->BaseAddress; - MPU->RASR = ((uint32_t)MPU_Init->DisableExec << MPU_RASR_XN_Pos) | - ((uint32_t)MPU_Init->AccessPermission << MPU_RASR_AP_Pos) | - ((uint32_t)MPU_Init->TypeExtField << MPU_RASR_TEX_Pos) | - ((uint32_t)MPU_Init->IsShareable << MPU_RASR_S_Pos) | - ((uint32_t)MPU_Init->IsCacheable << MPU_RASR_C_Pos) | - ((uint32_t)MPU_Init->IsBufferable << MPU_RASR_B_Pos) | - ((uint32_t)MPU_Init->SubRegionDisable << MPU_RASR_SRD_Pos) | - ((uint32_t)MPU_Init->Size << MPU_RASR_SIZE_Pos) | - ((uint32_t)MPU_Init->Enable << MPU_RASR_ENABLE_Pos); - } - else - { - MPU->RBAR = 0x00U; - MPU->RASR = 0x00U; - } -} -#endif /* __MPU_PRESENT */ - -/** - * @brief Gets the priority grouping field from the NVIC Interrupt Controller. - * @retval Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field) - */ -uint32_t HAL_NVIC_GetPriorityGrouping(void) -{ - /* Get the PRIGROUP[10:8] field value */ - return NVIC_GetPriorityGrouping(); -} - -/** - * @brief Gets the priority of an interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @param PriorityGroup the priority grouping bits length. - * This parameter can be one of the following values: - * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority - * 4 bits for subpriority - * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority - * 3 bits for subpriority - * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority - * 2 bits for subpriority - * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority - * 1 bits for subpriority - * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority - * 0 bits for subpriority - * @param pPreemptPriority Pointer on the Preemptive priority value (starting from 0). - * @param pSubPriority Pointer on the Subpriority value (starting from 0). - * @retval None - */ -void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t *pPreemptPriority, uint32_t *pSubPriority) -{ - /* Check the parameters */ - assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); - /* Get priority for Cortex-M system or device specific interrupts */ - NVIC_DecodePriority(NVIC_GetPriority(IRQn), PriorityGroup, pPreemptPriority, pSubPriority); -} - -/** - * @brief Sets Pending bit of an external interrupt. - * @param IRQn External interrupt number - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Set interrupt pending */ - NVIC_SetPendingIRQ(IRQn); -} - -/** - * @brief Gets Pending Interrupt (reads the pending register in the NVIC - * and returns the pending bit for the specified interrupt). - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval status: - 0 Interrupt status is not pending. - * - 1 Interrupt status is pending. - */ -uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Return 1 if pending else 0 */ - return NVIC_GetPendingIRQ(IRQn); -} - -/** - * @brief Clears the pending bit of an external interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Clear pending interrupt */ - NVIC_ClearPendingIRQ(IRQn); -} - -/** - * @brief Gets active interrupt ( reads the active register in NVIC and returns the active bit). - * @param IRQn External interrupt number - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval status: - 0 Interrupt status is not pending. - * - 1 Interrupt status is pending. - */ -uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Return 1 if active else 0 */ - return NVIC_GetActive(IRQn); -} - -/** - * @brief Configures the SysTick clock source. - * @param CLKSource specifies the SysTick clock source. - * This parameter can be one of the following values: - * @arg SYSTICK_CLKSOURCE_HCLK_DIV8: AHB clock divided by 8 selected as SysTick clock source. - * @arg SYSTICK_CLKSOURCE_HCLK: AHB clock selected as SysTick clock source. - * @retval None - */ -void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource) -{ - /* Check the parameters */ - assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource)); - if (CLKSource == SYSTICK_CLKSOURCE_HCLK) - { - SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; - } - else - { - SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK; - } -} - -/** - * @brief This function handles SYSTICK interrupt request. - * @retval None - */ -void HAL_SYSTICK_IRQHandler(void) -{ - HAL_SYSTICK_Callback(); -} - -/** - * @brief SYSTICK callback. - * @retval None - */ -__weak void HAL_SYSTICK_Callback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SYSTICK_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_CORTEX_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_cortex.c + * @author MCD Application Team + * @brief CORTEX HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the CORTEX: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + + [..] + *** How to configure Interrupts using CORTEX HAL driver *** + =========================================================== + [..] + This section provides functions allowing to configure the NVIC interrupts (IRQ). + The Cortex-M4 exceptions are managed by CMSIS functions. + + (#) Configure the NVIC Priority Grouping using HAL_NVIC_SetPriorityGrouping() + function according to the following table. + (#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority(). + (#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ(). + (#) please refer to programming manual for details in how to configure priority. + + -@- When the NVIC_PRIORITYGROUP_0 is selected, IRQ preemption is no more possible. + The pending IRQ priority will be managed only by the sub priority. + + -@- IRQ priority order (sorted by highest to lowest priority): + (+@) Lowest preemption priority + (+@) Lowest sub priority + (+@) Lowest hardware priority (IRQ number) + + [..] + *** How to configure Systick using CORTEX HAL driver *** + ======================================================== + [..] + Setup SysTick Timer for time base. + + (+) The HAL_SYSTICK_Config() function calls the SysTick_Config() function which + is a CMSIS function that: + (++) Configures the SysTick Reload register with value passed as function parameter. + (++) Configures the SysTick IRQ priority to the lowest value 0x0F. + (++) Resets the SysTick Counter register. + (++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK). + (++) Enables the SysTick Interrupt. + (++) Starts the SysTick Counter. + + (+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro + __HAL_CORTEX_SYSTICKCLK_CONFIG(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the + HAL_SYSTICK_Config() function call. The __HAL_CORTEX_SYSTICKCLK_CONFIG() macro is defined + inside the stm32f4xx_hal_cortex.h file. + + (+) You can change the SysTick IRQ priority by calling the + HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function + call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function. + + (+) To adjust the SysTick time base, use the following formula: + + Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s) + (++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function + (++) Reload Value should not exceed 0xFFFFFF + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup CORTEX CORTEX + * @brief CORTEX HAL module driver + * @{ + */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup CORTEX_Exported_Functions CORTEX Exported Functions + * @{ + */ + + +/** @defgroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides the CORTEX HAL driver functions allowing to configure Interrupts + Systick functionalities + +@endverbatim + * @{ + */ + + +/** + * @brief Sets the priority grouping field (preemption priority and subpriority) + * using the required unlock sequence. + * @param PriorityGroup The priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority + * 4 bits for subpriority + * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority + * 3 bits for subpriority + * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority + * 2 bits for subpriority + * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority + * 1 bits for subpriority + * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority + * 0 bits for subpriority + * @note When the NVIC_PriorityGroup_0 is selected, IRQ preemption is no more possible. + * The pending IRQ priority will be managed only by the subpriority. + * @retval None + */ +void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to the PriorityGroup parameter value */ + NVIC_SetPriorityGrouping(PriorityGroup); +} + +/** + * @brief Sets the priority of an interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @param PreemptPriority The preemption priority for the IRQn channel. + * This parameter can be a value between 0 and 15 + * A lower priority value indicates a higher priority + * @param SubPriority the subpriority level for the IRQ channel. + * This parameter can be a value between 0 and 15 + * A lower priority value indicates a higher priority. + * @retval None + */ +void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t prioritygroup = 0x00U; + + /* Check the parameters */ + assert_param(IS_NVIC_SUB_PRIORITY(SubPriority)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); + + prioritygroup = NVIC_GetPriorityGrouping(); + + NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); +} + +/** + * @brief Enables a device specific interrupt in the NVIC interrupt controller. + * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() + * function should be called before. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_EnableIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Enable interrupt */ + NVIC_EnableIRQ(IRQn); +} + +/** + * @brief Disables a device specific interrupt in the NVIC interrupt controller. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_DisableIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Disable interrupt */ + NVIC_DisableIRQ(IRQn); +} + +/** + * @brief Initiates a system reset request to reset the MCU. + * @retval None + */ +void HAL_NVIC_SystemReset(void) +{ + /* System Reset */ + NVIC_SystemReset(); +} + +/** + * @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer. + * Counter is in free running mode to generate periodic interrupts. + * @param TicksNumb Specifies the ticks Number of ticks between two interrupts. + * @retval status: - 0 Function succeeded. + * - 1 Function failed. + */ +uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb) +{ + return SysTick_Config(TicksNumb); +} +/** + * @} + */ + +/** @defgroup CORTEX_Exported_Functions_Group2 Peripheral Control functions + * @brief Cortex control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the CORTEX + (NVIC, SYSTICK, MPU) functionalities. + + +@endverbatim + * @{ + */ + +#if (__MPU_PRESENT == 1U) +/** + * @brief Disables the MPU + * @retval None + */ +void HAL_MPU_Disable(void) +{ + /* Make sure outstanding transfers are done */ + __DMB(); + + /* Disable fault exceptions */ + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; + + /* Disable the MPU and clear the control register*/ + MPU->CTRL = 0U; +} + +/** + * @brief Enable the MPU. + * @param MPU_Control Specifies the control mode of the MPU during hard fault, + * NMI, FAULTMASK and privileged access to the default memory + * This parameter can be one of the following values: + * @arg MPU_HFNMI_PRIVDEF_NONE + * @arg MPU_HARDFAULT_NMI + * @arg MPU_PRIVILEGED_DEFAULT + * @arg MPU_HFNMI_PRIVDEF + * @retval None + */ +void HAL_MPU_Enable(uint32_t MPU_Control) +{ + /* Enable the MPU */ + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; + + /* Enable fault exceptions */ + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; + + /* Ensure MPU setting take effects */ + __DSB(); + __ISB(); +} + +/** + * @brief Initializes and configures the Region and the memory to be protected. + * @param MPU_Init Pointer to a MPU_Region_InitTypeDef structure that contains + * the initialization and configuration information. + * @retval None + */ +void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init) +{ + /* Check the parameters */ + assert_param(IS_MPU_REGION_NUMBER(MPU_Init->Number)); + assert_param(IS_MPU_REGION_ENABLE(MPU_Init->Enable)); + + /* Set the Region number */ + MPU->RNR = MPU_Init->Number; + + if ((MPU_Init->Enable) != RESET) + { + /* Check the parameters */ + assert_param(IS_MPU_INSTRUCTION_ACCESS(MPU_Init->DisableExec)); + assert_param(IS_MPU_REGION_PERMISSION_ATTRIBUTE(MPU_Init->AccessPermission)); + assert_param(IS_MPU_TEX_LEVEL(MPU_Init->TypeExtField)); + assert_param(IS_MPU_ACCESS_SHAREABLE(MPU_Init->IsShareable)); + assert_param(IS_MPU_ACCESS_CACHEABLE(MPU_Init->IsCacheable)); + assert_param(IS_MPU_ACCESS_BUFFERABLE(MPU_Init->IsBufferable)); + assert_param(IS_MPU_SUB_REGION_DISABLE(MPU_Init->SubRegionDisable)); + assert_param(IS_MPU_REGION_SIZE(MPU_Init->Size)); + + MPU->RBAR = MPU_Init->BaseAddress; + MPU->RASR = ((uint32_t)MPU_Init->DisableExec << MPU_RASR_XN_Pos) | + ((uint32_t)MPU_Init->AccessPermission << MPU_RASR_AP_Pos) | + ((uint32_t)MPU_Init->TypeExtField << MPU_RASR_TEX_Pos) | + ((uint32_t)MPU_Init->IsShareable << MPU_RASR_S_Pos) | + ((uint32_t)MPU_Init->IsCacheable << MPU_RASR_C_Pos) | + ((uint32_t)MPU_Init->IsBufferable << MPU_RASR_B_Pos) | + ((uint32_t)MPU_Init->SubRegionDisable << MPU_RASR_SRD_Pos) | + ((uint32_t)MPU_Init->Size << MPU_RASR_SIZE_Pos) | + ((uint32_t)MPU_Init->Enable << MPU_RASR_ENABLE_Pos); + } + else + { + MPU->RBAR = 0x00U; + MPU->RASR = 0x00U; + } +} +#endif /* __MPU_PRESENT */ + +/** + * @brief Gets the priority grouping field from the NVIC Interrupt Controller. + * @retval Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field) + */ +uint32_t HAL_NVIC_GetPriorityGrouping(void) +{ + /* Get the PRIGROUP[10:8] field value */ + return NVIC_GetPriorityGrouping(); +} + +/** + * @brief Gets the priority of an interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @param PriorityGroup the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority + * 4 bits for subpriority + * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority + * 3 bits for subpriority + * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority + * 2 bits for subpriority + * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority + * 1 bits for subpriority + * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority + * 0 bits for subpriority + * @param pPreemptPriority Pointer on the Preemptive priority value (starting from 0). + * @param pSubPriority Pointer on the Subpriority value (starting from 0). + * @retval None + */ +void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t *pPreemptPriority, uint32_t *pSubPriority) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); + /* Get priority for Cortex-M system or device specific interrupts */ + NVIC_DecodePriority(NVIC_GetPriority(IRQn), PriorityGroup, pPreemptPriority, pSubPriority); +} + +/** + * @brief Sets Pending bit of an external interrupt. + * @param IRQn External interrupt number + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Set interrupt pending */ + NVIC_SetPendingIRQ(IRQn); +} + +/** + * @brief Gets Pending Interrupt (reads the pending register in the NVIC + * and returns the pending bit for the specified interrupt). + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval status: - 0 Interrupt status is not pending. + * - 1 Interrupt status is pending. + */ +uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Return 1 if pending else 0 */ + return NVIC_GetPendingIRQ(IRQn); +} + +/** + * @brief Clears the pending bit of an external interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Clear pending interrupt */ + NVIC_ClearPendingIRQ(IRQn); +} + +/** + * @brief Gets active interrupt ( reads the active register in NVIC and returns the active bit). + * @param IRQn External interrupt number + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval status: - 0 Interrupt status is not pending. + * - 1 Interrupt status is pending. + */ +uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Return 1 if active else 0 */ + return NVIC_GetActive(IRQn); +} + +/** + * @brief Configures the SysTick clock source. + * @param CLKSource specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SYSTICK_CLKSOURCE_HCLK_DIV8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SYSTICK_CLKSOURCE_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource)); + if (CLKSource == SYSTICK_CLKSOURCE_HCLK) + { + SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; + } + else + { + SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK; + } +} + +/** + * @brief This function handles SYSTICK interrupt request. + * @retval None + */ +void HAL_SYSTICK_IRQHandler(void) +{ + HAL_SYSTICK_Callback(); +} + +/** + * @brief SYSTICK callback. + * @retval None + */ +__weak void HAL_SYSTICK_Callback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SYSTICK_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_CORTEX_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c index 3dbb477..2bc5f27 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c @@ -1,1305 +1,1305 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma.c - * @author MCD Application Team - * @brief DMA HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the Direct Memory Access (DMA) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State and errors functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Enable and configure the peripheral to be connected to the DMA Stream - (except for internal SRAM/FLASH memories: no initialization is - necessary) please refer to Reference manual for connection between peripherals - and DMA requests. - - (#) For a given Stream, program the required configuration through the following parameters: - Transfer Direction, Source and Destination data formats, - Circular, Normal or peripheral flow control mode, Stream Priority level, - Source and Destination Increment mode, FIFO mode and its Threshold (if needed), - Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function. - - -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros: - __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE(). - - *** Polling mode IO operation *** - ================================= - [..] - (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source - address and destination address and the Length of data to be transferred. - (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this - case a fixed Timeout can be configured by User depending from his application. - (+) Use HAL_DMA_Abort() function to abort the current transfer. - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority() - (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ() - (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of - Source address and destination address and the Length of data to be transferred. In this - case the DMA interrupt is configured - (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine - (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can - add his own function by customization of function pointer XferCpltCallback and - XferErrorCallback (i.e a member of DMA handle structure). - [..] - (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error - detection. - - (#) Use HAL_DMA_Abort_IT() function to abort the current transfer - - -@- In Memory-to-Memory transfer mode, Circular mode is not allowed. - - -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is - possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set - Half-Word data size for the peripheral to access its data register and set Word data size - for the Memory to gain in access time. Each two half words will be packed and written in - a single access to a Word in the Memory). - - -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source - and Destination. In this case the Peripheral Data Size will be applied to both Source - and Destination. - - *** DMA HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DMA HAL driver. - - (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream. - (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream. - (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not. - - [..] - (@) You can refer to the DMA HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DMA DMA - * @brief DMA HAL module driver - * @{ - */ - -#ifdef HAL_DMA_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register */ - __IO uint32_t Reserved0; - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */ -} DMA_Base_Registers; - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup DMA_Private_Constants - * @{ - */ - #define HAL_TIMEOUT_DMA_ABORT 5U /* 5 ms */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DMA_Private_Functions - * @{ - */ -static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma); - -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ -/** @addtogroup DMA_Exported_Functions - * @{ - */ - -/** @addtogroup DMA_Exported_Functions_Group1 - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to initialize the DMA Stream source - and destination addresses, incrementation and data sizes, transfer direction, - circular/normal mode selection, memory-to-memory mode selection and Stream priority value. - [..] - The HAL_DMA_Init() function follows the DMA configuration procedures as described in - reference manual. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DMA according to the specified - * parameters in the DMA_InitTypeDef and create the associated handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma) -{ - uint32_t tmp = 0U; - uint32_t tickstart = HAL_GetTick(); - DMA_Base_Registers *regs; - - /* Check the DMA peripheral state */ - if(hdma == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); - assert_param(IS_DMA_CHANNEL(hdma->Init.Channel)); - assert_param(IS_DMA_DIRECTION(hdma->Init.Direction)); - assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc)); - assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc)); - assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment)); - assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment)); - assert_param(IS_DMA_MODE(hdma->Init.Mode)); - assert_param(IS_DMA_PRIORITY(hdma->Init.Priority)); - assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode)); - /* Check the memory burst, peripheral burst and FIFO threshold parameters only - when FIFO mode is enabled */ - if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE) - { - assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold)); - assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst)); - assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst)); - } - - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Allocate lock resource */ - __HAL_UNLOCK(hdma); - - /* Disable the peripheral */ - __HAL_DMA_DISABLE(hdma); - - /* Check if the DMA Stream is effectively disabled */ - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - } - - /* Get the CR register value */ - tmp = hdma->Instance->CR; - - /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */ - tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ - DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ - DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ - DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM)); - - /* Prepare the DMA Stream configuration */ - tmp |= hdma->Init.Channel | hdma->Init.Direction | - hdma->Init.PeriphInc | hdma->Init.MemInc | - hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | - hdma->Init.Mode | hdma->Init.Priority; - - /* the Memory burst and peripheral burst are not used when the FIFO is disabled */ - if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) - { - /* Get memory burst and peripheral burst */ - tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst; - } - - /* Write to DMA Stream CR register */ - hdma->Instance->CR = tmp; - - /* Get the FCR register value */ - tmp = hdma->Instance->FCR; - - /* Clear Direct mode and FIFO threshold bits */ - tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); - - /* Prepare the DMA Stream FIFO configuration */ - tmp |= hdma->Init.FIFOMode; - - /* The FIFO threshold is not used when the FIFO mode is disabled */ - if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) - { - /* Get the FIFO threshold */ - tmp |= hdma->Init.FIFOThreshold; - - /* Check compatibility between FIFO threshold level and size of the memory burst */ - /* for INCR4, INCR8, INCR16 bursts */ - if (hdma->Init.MemBurst != DMA_MBURST_SINGLE) - { - if (DMA_CheckFifoParam(hdma) != HAL_OK) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_PARAM; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - return HAL_ERROR; - } - } - } - - /* Write to DMA Stream FCR */ - hdma->Instance->FCR = tmp; - - /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate - DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */ - regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); - - /* Clear all interrupt flags */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Initialize the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the DMA peripheral - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma) -{ - DMA_Base_Registers *regs; - - /* Check the DMA peripheral state */ - if(hdma == NULL) - { - return HAL_ERROR; - } - - /* Check the DMA peripheral state */ - if(hdma->State == HAL_DMA_STATE_BUSY) - { - /* Return error status */ - return HAL_BUSY; - } - - /* Check the parameters */ - assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); - - /* Disable the selected DMA Streamx */ - __HAL_DMA_DISABLE(hdma); - - /* Reset DMA Streamx control register */ - hdma->Instance->CR = 0U; - - /* Reset DMA Streamx number of data to transfer register */ - hdma->Instance->NDTR = 0U; - - /* Reset DMA Streamx peripheral address register */ - hdma->Instance->PAR = 0U; - - /* Reset DMA Streamx memory 0 address register */ - hdma->Instance->M0AR = 0U; - - /* Reset DMA Streamx memory 1 address register */ - hdma->Instance->M1AR = 0U; - - /* Reset DMA Streamx FIFO control register */ - hdma->Instance->FCR = 0x00000021U; - - /* Get DMA steam Base Address */ - regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); - - /* Clean all callbacks */ - hdma->XferCpltCallback = NULL; - hdma->XferHalfCpltCallback = NULL; - hdma->XferM1CpltCallback = NULL; - hdma->XferM1HalfCpltCallback = NULL; - hdma->XferErrorCallback = NULL; - hdma->XferAbortCallback = NULL; - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Reset the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Reset the DMA state */ - hdma->State = HAL_DMA_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return HAL_OK; -} - -/** - * @} - */ - -/** @addtogroup DMA_Exported_Functions_Group2 - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the source, destination address and data length and Start DMA transfer - (+) Configure the source, destination address and data length and - Start DMA transfer with interrupt - (+) Abort DMA transfer - (+) Poll for transfer complete - (+) Handle DMA interrupt request - -@endverbatim - * @{ - */ - -/** - * @brief Starts the DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Configure the source, destination address and the data length */ - DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Enable the Peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - return status; -} - -/** - * @brief Start the DMA Transfer with interrupt enabled. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Configure the source, destination address and the data length */ - DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Enable Common interrupts*/ - hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; - - if(hdma->XferHalfCpltCallback != NULL) - { - hdma->Instance->CR |= DMA_IT_HT; - } - - /* Enable the Peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - - return status; -} - -/** - * @brief Aborts the DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * - * @note After disabling a DMA Stream, a check for wait until the DMA Stream is - * effectively disabled is added. If a Stream is disabled - * while a data transfer is ongoing, the current data will be transferred - * and the Stream will be effectively disabled only after the transfer of - * this single data is finished. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma) -{ - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - uint32_t tickstart = HAL_GetTick(); - - if(hdma->State != HAL_DMA_STATE_BUSY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_ERROR; - } - else - { - /* Disable all the transfer interrupts */ - hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); - hdma->Instance->FCR &= ~(DMA_IT_FE); - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - - /* Check if the DMA Stream is effectively disabled */ - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_TIMEOUT; - } - } - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Change the DMA state*/ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - return HAL_OK; -} - -/** - * @brief Aborts the DMA Transfer in Interrupt mode. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma) -{ - if(hdma->State != HAL_DMA_STATE_BUSY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - return HAL_ERROR; - } - else - { - /* Set Abort State */ - hdma->State = HAL_DMA_STATE_ABORT; - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - } - - return HAL_OK; -} - -/** - * @brief Polling for transfer complete. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CompleteLevel Specifies the DMA level complete. - * @note The polling mode is kept in this version for legacy. it is recommended to use the IT model instead. - * This model could be used for debug purpose. - * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode). - * @param Timeout Timeout duration. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t mask_cpltlevel; - uint32_t tickstart = HAL_GetTick(); - uint32_t tmpisr; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs; - - if(HAL_DMA_STATE_BUSY != hdma->State) - { - /* No transfer ongoing */ - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - __HAL_UNLOCK(hdma); - return HAL_ERROR; - } - - /* Polling mode not supported in circular mode and double buffering mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - return HAL_ERROR; - } - - /* Get the level transfer complete flag */ - if(CompleteLevel == HAL_DMA_FULL_TRANSFER) - { - /* Transfer Complete flag */ - mask_cpltlevel = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; - } - else - { - /* Half Transfer Complete flag */ - mask_cpltlevel = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; - } - - regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - tmpisr = regs->ISR; - - while(((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) - { - /* Check for the Timeout (Not applicable in circular mode)*/ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_TIMEOUT; - } - } - - /* Get the ISR register value */ - tmpisr = regs->ISR; - - if((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_TE; - - /* Clear the transfer error flag */ - regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; - } - - if((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_FE; - - /* Clear the FIFO error flag */ - regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; - } - - if((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_DME; - - /* Clear the Direct Mode error flag */ - regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; - } - } - - if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) - { - if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) - { - HAL_DMA_Abort(hdma); - - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; - - /* Change the DMA state */ - hdma->State= HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_ERROR; - } - } - - /* Get the level transfer complete flag */ - if(CompleteLevel == HAL_DMA_FULL_TRANSFER) - { - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; - - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - else - { - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; - } - - return status; -} - -/** - * @brief Handles DMA interrupt request. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval None - */ -void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma) -{ - uint32_t tmpisr; - __IO uint32_t count = 0U; - uint32_t timeout = SystemCoreClock / 9600U; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - tmpisr = regs->ISR; - - /* Transfer Error Interrupt management ***************************************/ - if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET) - { - /* Disable the transfer error interrupt */ - hdma->Instance->CR &= ~(DMA_IT_TE); - - /* Clear the transfer error flag */ - regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_TE; - } - } - /* FIFO Error Interrupt management ******************************************/ - if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET) - { - /* Clear the FIFO error flag */ - regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_FE; - } - } - /* Direct Mode Error Interrupt management ***********************************/ - if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET) - { - /* Clear the direct mode error flag */ - regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_DME; - } - } - /* Half Transfer Complete Interrupt management ******************************/ - if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET) - { - /* Clear the half transfer complete flag */ - regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; - - /* Multi_Buffering mode enabled */ - if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) - { - /* Current memory buffer used is Memory 0 */ - if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) - { - if(hdma->XferHalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferHalfCpltCallback(hdma); - } - } - /* Current memory buffer used is Memory 1 */ - else - { - if(hdma->XferM1HalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferM1HalfCpltCallback(hdma); - } - } - } - else - { - /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ - if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) - { - /* Disable the half transfer interrupt */ - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - if(hdma->XferHalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferHalfCpltCallback(hdma); - } - } - } - } - /* Transfer Complete Interrupt management ***********************************/ - if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET) - { - /* Clear the transfer complete flag */ - regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; - - if(HAL_DMA_STATE_ABORT == hdma->State) - { - /* Disable all the transfer interrupts */ - hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); - hdma->Instance->FCR &= ~(DMA_IT_FE); - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - if(hdma->XferAbortCallback != NULL) - { - hdma->XferAbortCallback(hdma); - } - return; - } - - if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) - { - /* Current memory buffer used is Memory 0 */ - if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) - { - if(hdma->XferM1CpltCallback != NULL) - { - /* Transfer complete Callback for memory1 */ - hdma->XferM1CpltCallback(hdma); - } - } - /* Current memory buffer used is Memory 1 */ - else - { - if(hdma->XferCpltCallback != NULL) - { - /* Transfer complete Callback for memory0 */ - hdma->XferCpltCallback(hdma); - } - } - } - /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ - else - { - if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) - { - /* Disable the transfer complete interrupt */ - hdma->Instance->CR &= ~(DMA_IT_TC); - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - - if(hdma->XferCpltCallback != NULL) - { - /* Transfer complete callback */ - hdma->XferCpltCallback(hdma); - } - } - } - } - - /* manage error case */ - if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) - { - if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) - { - hdma->State = HAL_DMA_STATE_ABORT; - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - - do - { - if (++count > timeout) - { - break; - } - } - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET); - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - - if(hdma->XferErrorCallback != NULL) - { - /* Transfer error callback */ - hdma->XferErrorCallback(hdma); - } - } -} - -/** - * @brief Register callbacks - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CallbackID User Callback identifier - * a DMA_HandleTypeDef structure as parameter. - * @param pCallback pointer to private callback function which has pointer to - * a DMA_HandleTypeDef structure as parameter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)) -{ - - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - switch (CallbackID) - { - case HAL_DMA_XFER_CPLT_CB_ID: - hdma->XferCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_HALFCPLT_CB_ID: - hdma->XferHalfCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_M1CPLT_CB_ID: - hdma->XferM1CpltCallback = pCallback; - break; - - case HAL_DMA_XFER_M1HALFCPLT_CB_ID: - hdma->XferM1HalfCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_ERROR_CB_ID: - hdma->XferErrorCallback = pCallback; - break; - - case HAL_DMA_XFER_ABORT_CB_ID: - hdma->XferAbortCallback = pCallback; - break; - - default: - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return status; -} - -/** - * @brief UnRegister callbacks - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CallbackID User Callback identifier - * a HAL_DMA_CallbackIDTypeDef ENUM as parameter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - switch (CallbackID) - { - case HAL_DMA_XFER_CPLT_CB_ID: - hdma->XferCpltCallback = NULL; - break; - - case HAL_DMA_XFER_HALFCPLT_CB_ID: - hdma->XferHalfCpltCallback = NULL; - break; - - case HAL_DMA_XFER_M1CPLT_CB_ID: - hdma->XferM1CpltCallback = NULL; - break; - - case HAL_DMA_XFER_M1HALFCPLT_CB_ID: - hdma->XferM1HalfCpltCallback = NULL; - break; - - case HAL_DMA_XFER_ERROR_CB_ID: - hdma->XferErrorCallback = NULL; - break; - - case HAL_DMA_XFER_ABORT_CB_ID: - hdma->XferAbortCallback = NULL; - break; - - case HAL_DMA_XFER_ALL_CB_ID: - hdma->XferCpltCallback = NULL; - hdma->XferHalfCpltCallback = NULL; - hdma->XferM1CpltCallback = NULL; - hdma->XferM1HalfCpltCallback = NULL; - hdma->XferErrorCallback = NULL; - hdma->XferAbortCallback = NULL; - break; - - default: - status = HAL_ERROR; - break; - } - } - else - { - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return status; -} - -/** - * @} - */ - -/** @addtogroup DMA_Exported_Functions_Group3 - * -@verbatim - =============================================================================== - ##### State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the DMA state - (+) Get error code - -@endverbatim - * @{ - */ - -/** - * @brief Returns the DMA state. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL state - */ -HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma) -{ - return hdma->State; -} - -/** - * @brief Return the DMA error code - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval DMA Error Code - */ -uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma) -{ - return hdma->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DMA_Private_Functions - * @{ - */ - -/** - * @brief Sets the DMA Transfer parameter. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - /* Clear DBM bit */ - hdma->Instance->CR &= (uint32_t)(~DMA_SxCR_DBM); - - /* Configure DMA Stream data length */ - hdma->Instance->NDTR = DataLength; - - /* Memory to Peripheral */ - if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) - { - /* Configure DMA Stream destination address */ - hdma->Instance->PAR = DstAddress; - - /* Configure DMA Stream source address */ - hdma->Instance->M0AR = SrcAddress; - } - /* Peripheral to Memory */ - else - { - /* Configure DMA Stream source address */ - hdma->Instance->PAR = SrcAddress; - - /* Configure DMA Stream destination address */ - hdma->Instance->M0AR = DstAddress; - } -} - -/** - * @brief Returns the DMA Stream base address depending on stream number - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval Stream base address - */ -static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma) -{ - uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U; - - /* lookup table for necessary bitshift of flags within status registers */ - static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U}; - hdma->StreamIndex = flagBitshiftOffset[stream_number]; - - if (stream_number > 3U) - { - /* return pointer to HISR and HIFCR */ - hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U); - } - else - { - /* return pointer to LISR and LIFCR */ - hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)); - } - - return hdma->StreamBaseAddress; -} - -/** - * @brief Check compatibility between FIFO threshold level and size of the memory burst - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmp = hdma->Init.FIFOThreshold; - - /* Memory Data size equal to Byte */ - if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE) - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_HALFFULL: - if (hdma->Init.MemBurst == DMA_MBURST_INC16) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_FULL: - break; - default: - break; - } - } - - /* Memory Data size equal to Half-Word */ - else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD) - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - status = HAL_ERROR; - break; - case DMA_FIFO_THRESHOLD_HALFFULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_FULL: - if (hdma->Init.MemBurst == DMA_MBURST_INC16) - { - status = HAL_ERROR; - } - break; - default: - break; - } - } - - /* Memory Data size equal to Word */ - else - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_HALFFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - status = HAL_ERROR; - break; - case DMA_FIFO_THRESHOLD_FULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - default: - break; - } - } - - return status; -} - -/** - * @} - */ - -#endif /* HAL_DMA_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma.c + * @author MCD Application Team + * @brief DMA HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the Direct Memory Access (DMA) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State and errors functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable and configure the peripheral to be connected to the DMA Stream + (except for internal SRAM/FLASH memories: no initialization is + necessary) please refer to Reference manual for connection between peripherals + and DMA requests. + + (#) For a given Stream, program the required configuration through the following parameters: + Transfer Direction, Source and Destination data formats, + Circular, Normal or peripheral flow control mode, Stream Priority level, + Source and Destination Increment mode, FIFO mode and its Threshold (if needed), + Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function. + + -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros: + __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE(). + + *** Polling mode IO operation *** + ================================= + [..] + (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source + address and destination address and the Length of data to be transferred. + (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this + case a fixed Timeout can be configured by User depending from his application. + (+) Use HAL_DMA_Abort() function to abort the current transfer. + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority() + (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ() + (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of + Source address and destination address and the Length of data to be transferred. In this + case the DMA interrupt is configured + (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine + (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can + add his own function by customization of function pointer XferCpltCallback and + XferErrorCallback (i.e a member of DMA handle structure). + [..] + (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error + detection. + + (#) Use HAL_DMA_Abort_IT() function to abort the current transfer + + -@- In Memory-to-Memory transfer mode, Circular mode is not allowed. + + -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is + possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set + Half-Word data size for the peripheral to access its data register and set Word data size + for the Memory to gain in access time. Each two half words will be packed and written in + a single access to a Word in the Memory). + + -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source + and Destination. In this case the Peripheral Data Size will be applied to both Source + and Destination. + + *** DMA HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DMA HAL driver. + + (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream. + (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream. + (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not. + + [..] + (@) You can refer to the DMA HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup DMA DMA + * @brief DMA HAL module driver + * @{ + */ + +#ifdef HAL_DMA_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register */ + __IO uint32_t Reserved0; + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */ +} DMA_Base_Registers; + +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup DMA_Private_Constants + * @{ + */ + #define HAL_TIMEOUT_DMA_ABORT 5U /* 5 ms */ +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup DMA_Private_Functions + * @{ + */ +static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma); + +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ +/** @addtogroup DMA_Exported_Functions + * @{ + */ + +/** @addtogroup DMA_Exported_Functions_Group1 + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to initialize the DMA Stream source + and destination addresses, incrementation and data sizes, transfer direction, + circular/normal mode selection, memory-to-memory mode selection and Stream priority value. + [..] + The HAL_DMA_Init() function follows the DMA configuration procedures as described in + reference manual. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DMA according to the specified + * parameters in the DMA_InitTypeDef and create the associated handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma) +{ + uint32_t tmp = 0U; + uint32_t tickstart = HAL_GetTick(); + DMA_Base_Registers *regs; + + /* Check the DMA peripheral state */ + if(hdma == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); + assert_param(IS_DMA_CHANNEL(hdma->Init.Channel)); + assert_param(IS_DMA_DIRECTION(hdma->Init.Direction)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment)); + assert_param(IS_DMA_MODE(hdma->Init.Mode)); + assert_param(IS_DMA_PRIORITY(hdma->Init.Priority)); + assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode)); + /* Check the memory burst, peripheral burst and FIFO threshold parameters only + when FIFO mode is enabled */ + if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE) + { + assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold)); + assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst)); + assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst)); + } + + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Allocate lock resource */ + __HAL_UNLOCK(hdma); + + /* Disable the peripheral */ + __HAL_DMA_DISABLE(hdma); + + /* Check if the DMA Stream is effectively disabled */ + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + } + + /* Get the CR register value */ + tmp = hdma->Instance->CR; + + /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */ + tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ + DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ + DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ + DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM)); + + /* Prepare the DMA Stream configuration */ + tmp |= hdma->Init.Channel | hdma->Init.Direction | + hdma->Init.PeriphInc | hdma->Init.MemInc | + hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | + hdma->Init.Mode | hdma->Init.Priority; + + /* the Memory burst and peripheral burst are not used when the FIFO is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + { + /* Get memory burst and peripheral burst */ + tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst; + } + + /* Write to DMA Stream CR register */ + hdma->Instance->CR = tmp; + + /* Get the FCR register value */ + tmp = hdma->Instance->FCR; + + /* Clear Direct mode and FIFO threshold bits */ + tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); + + /* Prepare the DMA Stream FIFO configuration */ + tmp |= hdma->Init.FIFOMode; + + /* The FIFO threshold is not used when the FIFO mode is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + { + /* Get the FIFO threshold */ + tmp |= hdma->Init.FIFOThreshold; + + /* Check compatibility between FIFO threshold level and size of the memory burst */ + /* for INCR4, INCR8, INCR16 bursts */ + if (hdma->Init.MemBurst != DMA_MBURST_SINGLE) + { + if (DMA_CheckFifoParam(hdma) != HAL_OK) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_PARAM; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + return HAL_ERROR; + } + } + } + + /* Write to DMA Stream FCR */ + hdma->Instance->FCR = tmp; + + /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate + DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */ + regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); + + /* Clear all interrupt flags */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Initialize the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the DMA peripheral + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma) +{ + DMA_Base_Registers *regs; + + /* Check the DMA peripheral state */ + if(hdma == NULL) + { + return HAL_ERROR; + } + + /* Check the DMA peripheral state */ + if(hdma->State == HAL_DMA_STATE_BUSY) + { + /* Return error status */ + return HAL_BUSY; + } + + /* Check the parameters */ + assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); + + /* Disable the selected DMA Streamx */ + __HAL_DMA_DISABLE(hdma); + + /* Reset DMA Streamx control register */ + hdma->Instance->CR = 0U; + + /* Reset DMA Streamx number of data to transfer register */ + hdma->Instance->NDTR = 0U; + + /* Reset DMA Streamx peripheral address register */ + hdma->Instance->PAR = 0U; + + /* Reset DMA Streamx memory 0 address register */ + hdma->Instance->M0AR = 0U; + + /* Reset DMA Streamx memory 1 address register */ + hdma->Instance->M1AR = 0U; + + /* Reset DMA Streamx FIFO control register */ + hdma->Instance->FCR = 0x00000021U; + + /* Get DMA steam Base Address */ + regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); + + /* Clean all callbacks */ + hdma->XferCpltCallback = NULL; + hdma->XferHalfCpltCallback = NULL; + hdma->XferM1CpltCallback = NULL; + hdma->XferM1HalfCpltCallback = NULL; + hdma->XferErrorCallback = NULL; + hdma->XferAbortCallback = NULL; + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Reset the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Reset the DMA state */ + hdma->State = HAL_DMA_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return HAL_OK; +} + +/** + * @} + */ + +/** @addtogroup DMA_Exported_Functions_Group2 + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the source, destination address and data length and Start DMA transfer + (+) Configure the source, destination address and data length and + Start DMA transfer with interrupt + (+) Abort DMA transfer + (+) Poll for transfer complete + (+) Handle DMA interrupt request + +@endverbatim + * @{ + */ + +/** + * @brief Starts the DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Configure the source, destination address and the data length */ + DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Enable the Peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + return status; +} + +/** + * @brief Start the DMA Transfer with interrupt enabled. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Configure the source, destination address and the data length */ + DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Enable Common interrupts*/ + hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; + + if(hdma->XferHalfCpltCallback != NULL) + { + hdma->Instance->CR |= DMA_IT_HT; + } + + /* Enable the Peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + + return status; +} + +/** + * @brief Aborts the DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * + * @note After disabling a DMA Stream, a check for wait until the DMA Stream is + * effectively disabled is added. If a Stream is disabled + * while a data transfer is ongoing, the current data will be transferred + * and the Stream will be effectively disabled only after the transfer of + * this single data is finished. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma) +{ + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + uint32_t tickstart = HAL_GetTick(); + + if(hdma->State != HAL_DMA_STATE_BUSY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_ERROR; + } + else + { + /* Disable all the transfer interrupts */ + hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); + hdma->Instance->FCR &= ~(DMA_IT_FE); + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + + /* Check if the DMA Stream is effectively disabled */ + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_TIMEOUT; + } + } + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Change the DMA state*/ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + return HAL_OK; +} + +/** + * @brief Aborts the DMA Transfer in Interrupt mode. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma) +{ + if(hdma->State != HAL_DMA_STATE_BUSY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + return HAL_ERROR; + } + else + { + /* Set Abort State */ + hdma->State = HAL_DMA_STATE_ABORT; + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + } + + return HAL_OK; +} + +/** + * @brief Polling for transfer complete. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CompleteLevel Specifies the DMA level complete. + * @note The polling mode is kept in this version for legacy. it is recommended to use the IT model instead. + * This model could be used for debug purpose. + * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode). + * @param Timeout Timeout duration. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t mask_cpltlevel; + uint32_t tickstart = HAL_GetTick(); + uint32_t tmpisr; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs; + + if(HAL_DMA_STATE_BUSY != hdma->State) + { + /* No transfer ongoing */ + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + /* Polling mode not supported in circular mode and double buffering mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + /* Get the level transfer complete flag */ + if(CompleteLevel == HAL_DMA_FULL_TRANSFER) + { + /* Transfer Complete flag */ + mask_cpltlevel = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; + } + else + { + /* Half Transfer Complete flag */ + mask_cpltlevel = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; + } + + regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + tmpisr = regs->ISR; + + while(((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) + { + /* Check for the Timeout (Not applicable in circular mode)*/ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_TIMEOUT; + } + } + + /* Get the ISR register value */ + tmpisr = regs->ISR; + + if((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_TE; + + /* Clear the transfer error flag */ + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; + } + + if((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_FE; + + /* Clear the FIFO error flag */ + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; + } + + if((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_DME; + + /* Clear the Direct Mode error flag */ + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; + } + } + + if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) + { + if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) + { + HAL_DMA_Abort(hdma); + + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; + + /* Change the DMA state */ + hdma->State= HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_ERROR; + } + } + + /* Get the level transfer complete flag */ + if(CompleteLevel == HAL_DMA_FULL_TRANSFER) + { + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; + + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + else + { + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; + } + + return status; +} + +/** + * @brief Handles DMA interrupt request. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval None + */ +void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma) +{ + uint32_t tmpisr; + __IO uint32_t count = 0U; + uint32_t timeout = SystemCoreClock / 9600U; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + tmpisr = regs->ISR; + + /* Transfer Error Interrupt management ***************************************/ + if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET) + { + /* Disable the transfer error interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TE); + + /* Clear the transfer error flag */ + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_TE; + } + } + /* FIFO Error Interrupt management ******************************************/ + if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET) + { + /* Clear the FIFO error flag */ + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_FE; + } + } + /* Direct Mode Error Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET) + { + /* Clear the direct mode error flag */ + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_DME; + } + } + /* Half Transfer Complete Interrupt management ******************************/ + if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET) + { + /* Clear the half transfer complete flag */ + regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; + + /* Multi_Buffering mode enabled */ + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + { + if(hdma->XferHalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferM1HalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferM1HalfCpltCallback(hdma); + } + } + } + else + { + /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + { + /* Disable the half transfer interrupt */ + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + if(hdma->XferHalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + } + } + } + } + /* Transfer Complete Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET) + { + /* Clear the transfer complete flag */ + regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; + + if(HAL_DMA_STATE_ABORT == hdma->State) + { + /* Disable all the transfer interrupts */ + hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); + hdma->Instance->FCR &= ~(DMA_IT_FE); + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + if(hdma->XferAbortCallback != NULL) + { + hdma->XferAbortCallback(hdma); + } + return; + } + + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + { + if(hdma->XferM1CpltCallback != NULL) + { + /* Transfer complete Callback for memory1 */ + hdma->XferM1CpltCallback(hdma); + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferCpltCallback != NULL) + { + /* Transfer complete Callback for memory0 */ + hdma->XferCpltCallback(hdma); + } + } + } + /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ + else + { + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + { + /* Disable the transfer complete interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TC); + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + + if(hdma->XferCpltCallback != NULL) + { + /* Transfer complete callback */ + hdma->XferCpltCallback(hdma); + } + } + } + } + + /* manage error case */ + if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) + { + if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) + { + hdma->State = HAL_DMA_STATE_ABORT; + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + + do + { + if (++count > timeout) + { + break; + } + } + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET); + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + + if(hdma->XferErrorCallback != NULL) + { + /* Transfer error callback */ + hdma->XferErrorCallback(hdma); + } + } +} + +/** + * @brief Register callbacks + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CallbackID User Callback identifier + * a DMA_HandleTypeDef structure as parameter. + * @param pCallback pointer to private callback function which has pointer to + * a DMA_HandleTypeDef structure as parameter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)) +{ + + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + switch (CallbackID) + { + case HAL_DMA_XFER_CPLT_CB_ID: + hdma->XferCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_HALFCPLT_CB_ID: + hdma->XferHalfCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_M1CPLT_CB_ID: + hdma->XferM1CpltCallback = pCallback; + break; + + case HAL_DMA_XFER_M1HALFCPLT_CB_ID: + hdma->XferM1HalfCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_ERROR_CB_ID: + hdma->XferErrorCallback = pCallback; + break; + + case HAL_DMA_XFER_ABORT_CB_ID: + hdma->XferAbortCallback = pCallback; + break; + + default: + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return status; +} + +/** + * @brief UnRegister callbacks + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CallbackID User Callback identifier + * a HAL_DMA_CallbackIDTypeDef ENUM as parameter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + switch (CallbackID) + { + case HAL_DMA_XFER_CPLT_CB_ID: + hdma->XferCpltCallback = NULL; + break; + + case HAL_DMA_XFER_HALFCPLT_CB_ID: + hdma->XferHalfCpltCallback = NULL; + break; + + case HAL_DMA_XFER_M1CPLT_CB_ID: + hdma->XferM1CpltCallback = NULL; + break; + + case HAL_DMA_XFER_M1HALFCPLT_CB_ID: + hdma->XferM1HalfCpltCallback = NULL; + break; + + case HAL_DMA_XFER_ERROR_CB_ID: + hdma->XferErrorCallback = NULL; + break; + + case HAL_DMA_XFER_ABORT_CB_ID: + hdma->XferAbortCallback = NULL; + break; + + case HAL_DMA_XFER_ALL_CB_ID: + hdma->XferCpltCallback = NULL; + hdma->XferHalfCpltCallback = NULL; + hdma->XferM1CpltCallback = NULL; + hdma->XferM1HalfCpltCallback = NULL; + hdma->XferErrorCallback = NULL; + hdma->XferAbortCallback = NULL; + break; + + default: + status = HAL_ERROR; + break; + } + } + else + { + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return status; +} + +/** + * @} + */ + +/** @addtogroup DMA_Exported_Functions_Group3 + * +@verbatim + =============================================================================== + ##### State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the DMA state + (+) Get error code + +@endverbatim + * @{ + */ + +/** + * @brief Returns the DMA state. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL state + */ +HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma) +{ + return hdma->State; +} + +/** + * @brief Return the DMA error code + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval DMA Error Code + */ +uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma) +{ + return hdma->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DMA_Private_Functions + * @{ + */ + +/** + * @brief Sets the DMA Transfer parameter. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + /* Clear DBM bit */ + hdma->Instance->CR &= (uint32_t)(~DMA_SxCR_DBM); + + /* Configure DMA Stream data length */ + hdma->Instance->NDTR = DataLength; + + /* Memory to Peripheral */ + if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) + { + /* Configure DMA Stream destination address */ + hdma->Instance->PAR = DstAddress; + + /* Configure DMA Stream source address */ + hdma->Instance->M0AR = SrcAddress; + } + /* Peripheral to Memory */ + else + { + /* Configure DMA Stream source address */ + hdma->Instance->PAR = SrcAddress; + + /* Configure DMA Stream destination address */ + hdma->Instance->M0AR = DstAddress; + } +} + +/** + * @brief Returns the DMA Stream base address depending on stream number + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval Stream base address + */ +static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma) +{ + uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U; + + /* lookup table for necessary bitshift of flags within status registers */ + static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U}; + hdma->StreamIndex = flagBitshiftOffset[stream_number]; + + if (stream_number > 3U) + { + /* return pointer to HISR and HIFCR */ + hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U); + } + else + { + /* return pointer to LISR and LIFCR */ + hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)); + } + + return hdma->StreamBaseAddress; +} + +/** + * @brief Check compatibility between FIFO threshold level and size of the memory burst + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmp = hdma->Init.FIFOThreshold; + + /* Memory Data size equal to Byte */ + if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE) + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_HALFFULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_FULL: + break; + default: + break; + } + } + + /* Memory Data size equal to Half-Word */ + else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD) + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + status = HAL_ERROR; + break; + case DMA_FIFO_THRESHOLD_HALFFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_FULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + { + status = HAL_ERROR; + } + break; + default: + break; + } + } + + /* Memory Data size equal to Word */ + else + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_HALFFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + status = HAL_ERROR; + break; + case DMA_FIFO_THRESHOLD_FULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + default: + break; + } + } + + return status; +} + +/** + * @} + */ + +#endif /* HAL_DMA_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c index 7167e77..d38cfcd 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c @@ -1,313 +1,313 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma_ex.c - * @author MCD Application Team - * @brief DMA Extension HAL module driver - * This file provides firmware functions to manage the following - * functionalities of the DMA Extension peripheral: - * + Extended features functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The DMA Extension HAL driver can be used as follows: - (#) Start a multi buffer transfer using the HAL_DMA_MultiBufferStart() function - for polling mode or HAL_DMA_MultiBufferStart_IT() for interrupt mode. - - -@- In Memory-to-Memory transfer mode, Multi (Double) Buffer mode is not allowed. - -@- When Multi (Double) Buffer mode is enabled the, transfer is circular by default. - -@- In Multi (Double) buffer mode, it is possible to update the base address for - the AHB memory port on the fly (DMA_SxM0AR or DMA_SxM1AR) when the stream is enabled. - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DMAEx DMAEx - * @brief DMA Extended HAL module driver - * @{ - */ - -#ifdef HAL_DMA_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private Constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DMAEx_Private_Functions - * @{ - */ -static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ - -/** @addtogroup DMAEx_Exported_Functions - * @{ - */ - - -/** @addtogroup DMAEx_Exported_Functions_Group1 - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the source, destination address and data length and - Start MultiBuffer DMA transfer - (+) Configure the source, destination address and data length and - Start MultiBuffer DMA transfer with interrupt - (+) Change on the fly the memory0 or memory1 address. - -@endverbatim - * @{ - */ - - -/** - * @brief Starts the multi_buffer DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Memory-to-memory transfer not supported in double buffering mode */ - if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - status = HAL_ERROR; - } - else - { - /* Process Locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Enable the double buffer mode */ - hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; - - /* Configure DMA Stream destination address */ - hdma->Instance->M1AR = SecondMemAddress; - - /* Configure the source, destination address and the data length */ - DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Enable the peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Return error status */ - status = HAL_BUSY; - } - } - return status; -} - -/** - * @brief Starts the multi_buffer DMA Transfer with interrupt enabled. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Memory-to-memory transfer not supported in double buffering mode */ - if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - return HAL_ERROR; - } - - /* Check callback functions */ - if ((NULL == hdma->XferCpltCallback) || (NULL == hdma->XferM1CpltCallback) || (NULL == hdma->XferErrorCallback)) - { - hdma->ErrorCode = HAL_DMA_ERROR_PARAM; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Enable the Double buffer mode */ - hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; - - /* Configure DMA Stream destination address */ - hdma->Instance->M1AR = SecondMemAddress; - - /* Configure the source, destination address and the data length */ - DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Clear all flags */ - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_DME_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_FE_FLAG_INDEX(hdma)); - - /* Enable Common interrupts*/ - hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; - hdma->Instance->FCR |= DMA_IT_FE; - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR |= DMA_IT_HT; - } - - /* Enable the peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - return status; -} - -/** - * @brief Change the memory0 or memory1 address on the fly. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param Address The new address - * @param memory the memory to be changed, This parameter can be one of - * the following values: - * MEMORY0 / - * MEMORY1 - * @note The MEMORY0 address can be changed only when the current transfer use - * MEMORY1 and the MEMORY1 address can be changed only when the current - * transfer use MEMORY0. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory) -{ - if(memory == MEMORY0) - { - /* change the memory0 address */ - hdma->Instance->M0AR = Address; - } - else - { - /* change the memory1 address */ - hdma->Instance->M1AR = Address; - } - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DMAEx_Private_Functions - * @{ - */ - -/** - * @brief Set the DMA Transfer parameter. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - /* Configure DMA Stream data length */ - hdma->Instance->NDTR = DataLength; - - /* Peripheral to Memory */ - if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) - { - /* Configure DMA Stream destination address */ - hdma->Instance->PAR = DstAddress; - - /* Configure DMA Stream source address */ - hdma->Instance->M0AR = SrcAddress; - } - /* Memory to Peripheral */ - else - { - /* Configure DMA Stream source address */ - hdma->Instance->PAR = SrcAddress; - - /* Configure DMA Stream destination address */ - hdma->Instance->M0AR = DstAddress; - } -} - -/** - * @} - */ - -#endif /* HAL_DMA_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma_ex.c + * @author MCD Application Team + * @brief DMA Extension HAL module driver + * This file provides firmware functions to manage the following + * functionalities of the DMA Extension peripheral: + * + Extended features functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The DMA Extension HAL driver can be used as follows: + (#) Start a multi buffer transfer using the HAL_DMA_MultiBufferStart() function + for polling mode or HAL_DMA_MultiBufferStart_IT() for interrupt mode. + + -@- In Memory-to-Memory transfer mode, Multi (Double) Buffer mode is not allowed. + -@- When Multi (Double) Buffer mode is enabled the, transfer is circular by default. + -@- In Multi (Double) buffer mode, it is possible to update the base address for + the AHB memory port on the fly (DMA_SxM0AR or DMA_SxM1AR) when the stream is enabled. + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup DMAEx DMAEx + * @brief DMA Extended HAL module driver + * @{ + */ + +#ifdef HAL_DMA_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private Constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup DMAEx_Private_Functions + * @{ + */ +static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ + +/** @addtogroup DMAEx_Exported_Functions + * @{ + */ + + +/** @addtogroup DMAEx_Exported_Functions_Group1 + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the source, destination address and data length and + Start MultiBuffer DMA transfer + (+) Configure the source, destination address and data length and + Start MultiBuffer DMA transfer with interrupt + (+) Change on the fly the memory0 or memory1 address. + +@endverbatim + * @{ + */ + + +/** + * @brief Starts the multi_buffer DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Memory-to-memory transfer not supported in double buffering mode */ + if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + status = HAL_ERROR; + } + else + { + /* Process Locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Enable the double buffer mode */ + hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; + + /* Configure DMA Stream destination address */ + hdma->Instance->M1AR = SecondMemAddress; + + /* Configure the source, destination address and the data length */ + DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Enable the peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Return error status */ + status = HAL_BUSY; + } + } + return status; +} + +/** + * @brief Starts the multi_buffer DMA Transfer with interrupt enabled. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Memory-to-memory transfer not supported in double buffering mode */ + if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + /* Check callback functions */ + if ((NULL == hdma->XferCpltCallback) || (NULL == hdma->XferM1CpltCallback) || (NULL == hdma->XferErrorCallback)) + { + hdma->ErrorCode = HAL_DMA_ERROR_PARAM; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Enable the Double buffer mode */ + hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; + + /* Configure DMA Stream destination address */ + hdma->Instance->M1AR = SecondMemAddress; + + /* Configure the source, destination address and the data length */ + DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Clear all flags */ + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_DME_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_FE_FLAG_INDEX(hdma)); + + /* Enable Common interrupts*/ + hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; + hdma->Instance->FCR |= DMA_IT_FE; + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR |= DMA_IT_HT; + } + + /* Enable the peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + return status; +} + +/** + * @brief Change the memory0 or memory1 address on the fly. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param Address The new address + * @param memory the memory to be changed, This parameter can be one of + * the following values: + * MEMORY0 / + * MEMORY1 + * @note The MEMORY0 address can be changed only when the current transfer use + * MEMORY1 and the MEMORY1 address can be changed only when the current + * transfer use MEMORY0. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory) +{ + if(memory == MEMORY0) + { + /* change the memory0 address */ + hdma->Instance->M0AR = Address; + } + else + { + /* change the memory1 address */ + hdma->Instance->M1AR = Address; + } + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DMAEx_Private_Functions + * @{ + */ + +/** + * @brief Set the DMA Transfer parameter. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + /* Configure DMA Stream data length */ + hdma->Instance->NDTR = DataLength; + + /* Peripheral to Memory */ + if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) + { + /* Configure DMA Stream destination address */ + hdma->Instance->PAR = DstAddress; + + /* Configure DMA Stream source address */ + hdma->Instance->M0AR = SrcAddress; + } + /* Memory to Peripheral */ + else + { + /* Configure DMA Stream source address */ + hdma->Instance->PAR = SrcAddress; + + /* Configure DMA Stream destination address */ + hdma->Instance->M0AR = DstAddress; + } +} + +/** + * @} + */ + +#endif /* HAL_DMA_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c index 04b5215..f0eff70 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c @@ -1,547 +1,547 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_exti.c - * @author MCD Application Team - * @brief EXTI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Extended Interrupts and events controller (EXTI) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2018 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### EXTI Peripheral features ##### - ============================================================================== - [..] - (+) Each Exti line can be configured within this driver. - - (+) Exti line can be configured in 3 different modes - (++) Interrupt - (++) Event - (++) Both of them - - (+) Configurable Exti lines can be configured with 3 different triggers - (++) Rising - (++) Falling - (++) Both of them - - (+) When set in interrupt mode, configurable Exti lines have two different - interrupts pending registers which allow to distinguish which transition - occurs: - (++) Rising edge pending interrupt - (++) Falling - - (+) Exti lines 0 to 15 are linked to gpio pin number 0 to 15. Gpio port can - be selected through multiplexer. - - ##### How to use this driver ##### - ============================================================================== - [..] - - (#) Configure the EXTI line using HAL_EXTI_SetConfigLine(). - (++) Choose the interrupt line number by setting "Line" member from - EXTI_ConfigTypeDef structure. - (++) Configure the interrupt and/or event mode using "Mode" member from - EXTI_ConfigTypeDef structure. - (++) For configurable lines, configure rising and/or falling trigger - "Trigger" member from EXTI_ConfigTypeDef structure. - (++) For Exti lines linked to gpio, choose gpio port using "GPIOSel" - member from GPIO_InitTypeDef structure. - - (#) Get current Exti configuration of a dedicated line using - HAL_EXTI_GetConfigLine(). - (++) Provide exiting handle as parameter. - (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter. - - (#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine(). - (++) Provide exiting handle as parameter. - - (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback(). - (++) Provide exiting handle as first parameter. - (++) Provide which callback will be registered using one value from - EXTI_CallbackIDTypeDef. - (++) Provide callback function pointer. - - (#) Get interrupt pending bit using HAL_EXTI_GetPending(). - - (#) Clear interrupt pending bit using HAL_EXTI_GetPending(). - - (#) Generate software interrupt using HAL_EXTI_GenerateSWI(). - - @endverbatim - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup EXTI - * @{ - */ -/** MISRA C:2012 deviation rule has been granted for following rule: - * Rule-18.1_b - Medium: Array `EXTICR' 1st subscript interval [0,7] may be out - * of bounds [0,3] in following API : - * HAL_EXTI_SetConfigLine - * HAL_EXTI_GetConfigLine - * HAL_EXTI_ClearConfigLine - */ - -#ifdef HAL_EXTI_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup EXTI_Private_Constants EXTI Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup EXTI_Exported_Functions - * @{ - */ - -/** @addtogroup EXTI_Exported_Functions_Group1 - * @brief Configuration functions - * -@verbatim - =============================================================================== - ##### Configuration functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Set configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @param pExtiConfig Pointer on EXTI configuration to be set. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if ((hexti == NULL) || (pExtiConfig == NULL)) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_EXTI_LINE(pExtiConfig->Line)); - assert_param(IS_EXTI_MODE(pExtiConfig->Mode)); - - /* Assign line number to handle */ - hexti->Line = pExtiConfig->Line; - - /* Compute line mask */ - linepos = (pExtiConfig->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* Configure triggers for configurable lines */ - if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) - { - assert_param(IS_EXTI_TRIGGER(pExtiConfig->Trigger)); - - /* Configure rising trigger */ - /* Mask or set line */ - if ((pExtiConfig->Trigger & EXTI_TRIGGER_RISING) != 0x00u) - { - EXTI->RTSR |= maskline; - } - else - { - EXTI->RTSR &= ~maskline; - } - - /* Configure falling trigger */ - /* Mask or set line */ - if ((pExtiConfig->Trigger & EXTI_TRIGGER_FALLING) != 0x00u) - { - EXTI->FTSR |= maskline; - } - else - { - EXTI->FTSR &= ~maskline; - } - - - /* Configure gpio port selection in case of gpio exti line */ - if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PORT(pExtiConfig->GPIOSel)); - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = SYSCFG->EXTICR[linepos >> 2u]; - regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - regval |= (pExtiConfig->GPIOSel << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - SYSCFG->EXTICR[linepos >> 2u] = regval; - } - } - - /* Configure interrupt mode : read current mode */ - /* Mask or set line */ - if ((pExtiConfig->Mode & EXTI_MODE_INTERRUPT) != 0x00u) - { - EXTI->IMR |= maskline; - } - else - { - EXTI->IMR &= ~maskline; - } - - /* Configure event mode : read current mode */ - /* Mask or set line */ - if ((pExtiConfig->Mode & EXTI_MODE_EVENT) != 0x00u) - { - EXTI->EMR |= maskline; - } - else - { - EXTI->EMR &= ~maskline; - } - - return HAL_OK; -} - -/** - * @brief Get configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @param pExtiConfig Pointer on structure to store Exti configuration. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if ((hexti == NULL) || (pExtiConfig == NULL)) - { - return HAL_ERROR; - } - - /* Check the parameter */ - assert_param(IS_EXTI_LINE(hexti->Line)); - - /* Store handle line number to configuration structure */ - pExtiConfig->Line = hexti->Line; - - /* Compute line mask */ - linepos = (pExtiConfig->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* 1] Get core mode : interrupt */ - - /* Check if selected line is enable */ - if ((EXTI->IMR & maskline) != 0x00u) - { - pExtiConfig->Mode = EXTI_MODE_INTERRUPT; - } - else - { - pExtiConfig->Mode = EXTI_MODE_NONE; - } - - /* Get event mode */ - /* Check if selected line is enable */ - if ((EXTI->EMR & maskline) != 0x00u) - { - pExtiConfig->Mode |= EXTI_MODE_EVENT; - } - - /* Get default Trigger and GPIOSel configuration */ - pExtiConfig->Trigger = EXTI_TRIGGER_NONE; - pExtiConfig->GPIOSel = 0x00u; - - /* 2] Get trigger for configurable lines : rising */ - if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) - { - /* Check if configuration of selected line is enable */ - if ((EXTI->RTSR & maskline) != 0x00u) - { - pExtiConfig->Trigger = EXTI_TRIGGER_RISING; - } - - /* Get falling configuration */ - /* Check if configuration of selected line is enable */ - if ((EXTI->FTSR & maskline) != 0x00u) - { - pExtiConfig->Trigger |= EXTI_TRIGGER_FALLING; - } - - /* Get Gpio port selection for gpio lines */ - if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = (SYSCFG->EXTICR[linepos >> 2u] << 16u ); - pExtiConfig->GPIOSel = ((regval << (SYSCFG_EXTICR1_EXTI1_Pos * (3uL - (linepos & 0x03u)))) >> 28u); - } - } - - return HAL_OK; -} - -/** - * @brief Clear whole configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if (hexti == NULL) - { - return HAL_ERROR; - } - - /* Check the parameter */ - assert_param(IS_EXTI_LINE(hexti->Line)); - - /* compute line mask */ - linepos = (hexti->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* 1] Clear interrupt mode */ - EXTI->IMR = (EXTI->IMR & ~maskline); - - /* 2] Clear event mode */ - EXTI->EMR = (EXTI->EMR & ~maskline); - - /* 3] Clear triggers in case of configurable lines */ - if ((hexti->Line & EXTI_CONFIG) != 0x00u) - { - EXTI->RTSR = (EXTI->RTSR & ~maskline); - EXTI->FTSR = (EXTI->FTSR & ~maskline); - - /* Get Gpio port selection for gpio lines */ - if ((hexti->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = SYSCFG->EXTICR[linepos >> 2u]; - regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - SYSCFG->EXTICR[linepos >> 2u] = regval; - } - } - - return HAL_OK; -} - -/** - * @brief Register callback for a dedicated Exti line. - * @param hexti Exti handle. - * @param CallbackID User callback identifier. - * This parameter can be one of @arg @ref EXTI_CallbackIDTypeDef values. - * @param pPendingCbfn function pointer to be stored as callback. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)) -{ - HAL_StatusTypeDef status = HAL_OK; - - switch (CallbackID) - { - case HAL_EXTI_COMMON_CB_ID: - hexti->PendingCallback = pPendingCbfn; - break; - - default: - status = HAL_ERROR; - break; - } - - return status; -} - -/** - * @brief Store line number as handle private field. - * @param hexti Exti handle. - * @param ExtiLine Exti line number. - * This parameter can be from 0 to @ref EXTI_LINE_NB. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine) -{ - /* Check the parameters */ - assert_param(IS_EXTI_LINE(ExtiLine)); - - /* Check null pointer */ - if (hexti == NULL) - { - return HAL_ERROR; - } - else - { - /* Store line number as handle private field */ - hexti->Line = ExtiLine; - - return HAL_OK; - } -} - -/** - * @} - */ - -/** @addtogroup EXTI_Exported_Functions_Group2 - * @brief EXTI IO functions. - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Handle EXTI interrupt request. - * @param hexti Exti handle. - * @retval none. - */ -void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti) -{ - uint32_t regval; - uint32_t maskline; - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Get pending bit */ - regval = (EXTI->PR & maskline); - if (regval != 0x00u) - { - /* Clear pending bit */ - EXTI->PR = maskline; - - /* Call callback */ - if (hexti->PendingCallback != NULL) - { - hexti->PendingCallback(); - } - } -} - -/** - * @brief Get interrupt pending bit of a dedicated line. - * @param hexti Exti handle. - * @param Edge Specify which pending edge as to be checked. - * This parameter can be one of the following values: - * @arg @ref EXTI_TRIGGER_RISING_FALLING - * This parameter is kept for compatibility with other series. - * @retval 1 if interrupt is pending else 0. - */ -uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - assert_param(IS_EXTI_PENDING_EDGE(Edge)); - - /* Compute line mask */ - linepos = (hexti->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* return 1 if bit is set else 0 */ - regval = ((EXTI->PR & maskline) >> linepos); - return regval; -} - -/** - * @brief Clear interrupt pending bit of a dedicated line. - * @param hexti Exti handle. - * @param Edge Specify which pending edge as to be clear. - * This parameter can be one of the following values: - * @arg @ref EXTI_TRIGGER_RISING_FALLING - * This parameter is kept for compatibility with other series. - * @retval None. - */ -void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) -{ - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - assert_param(IS_EXTI_PENDING_EDGE(Edge)); - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Clear Pending bit */ - EXTI->PR = maskline; -} - -/** - * @brief Generate a software interrupt for a dedicated line. - * @param hexti Exti handle. - * @retval None. - */ -void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti) -{ - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Generate Software interrupt */ - EXTI->SWIER = maskline; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_EXTI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_exti.c + * @author MCD Application Team + * @brief EXTI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Extended Interrupts and events controller (EXTI) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2018 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### EXTI Peripheral features ##### + ============================================================================== + [..] + (+) Each Exti line can be configured within this driver. + + (+) Exti line can be configured in 3 different modes + (++) Interrupt + (++) Event + (++) Both of them + + (+) Configurable Exti lines can be configured with 3 different triggers + (++) Rising + (++) Falling + (++) Both of them + + (+) When set in interrupt mode, configurable Exti lines have two different + interrupts pending registers which allow to distinguish which transition + occurs: + (++) Rising edge pending interrupt + (++) Falling + + (+) Exti lines 0 to 15 are linked to gpio pin number 0 to 15. Gpio port can + be selected through multiplexer. + + ##### How to use this driver ##### + ============================================================================== + [..] + + (#) Configure the EXTI line using HAL_EXTI_SetConfigLine(). + (++) Choose the interrupt line number by setting "Line" member from + EXTI_ConfigTypeDef structure. + (++) Configure the interrupt and/or event mode using "Mode" member from + EXTI_ConfigTypeDef structure. + (++) For configurable lines, configure rising and/or falling trigger + "Trigger" member from EXTI_ConfigTypeDef structure. + (++) For Exti lines linked to gpio, choose gpio port using "GPIOSel" + member from GPIO_InitTypeDef structure. + + (#) Get current Exti configuration of a dedicated line using + HAL_EXTI_GetConfigLine(). + (++) Provide exiting handle as parameter. + (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter. + + (#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine(). + (++) Provide exiting handle as parameter. + + (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback(). + (++) Provide exiting handle as first parameter. + (++) Provide which callback will be registered using one value from + EXTI_CallbackIDTypeDef. + (++) Provide callback function pointer. + + (#) Get interrupt pending bit using HAL_EXTI_GetPending(). + + (#) Clear interrupt pending bit using HAL_EXTI_GetPending(). + + (#) Generate software interrupt using HAL_EXTI_GenerateSWI(). + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ +/** MISRA C:2012 deviation rule has been granted for following rule: + * Rule-18.1_b - Medium: Array `EXTICR' 1st subscript interval [0,7] may be out + * of bounds [0,3] in following API : + * HAL_EXTI_SetConfigLine + * HAL_EXTI_GetConfigLine + * HAL_EXTI_ClearConfigLine + */ + +#ifdef HAL_EXTI_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/** @defgroup EXTI_Private_Constants EXTI Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup EXTI_Exported_Functions + * @{ + */ + +/** @addtogroup EXTI_Exported_Functions_Group1 + * @brief Configuration functions + * +@verbatim + =============================================================================== + ##### Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Set configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @param pExtiConfig Pointer on EXTI configuration to be set. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if ((hexti == NULL) || (pExtiConfig == NULL)) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_EXTI_LINE(pExtiConfig->Line)); + assert_param(IS_EXTI_MODE(pExtiConfig->Mode)); + + /* Assign line number to handle */ + hexti->Line = pExtiConfig->Line; + + /* Compute line mask */ + linepos = (pExtiConfig->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* Configure triggers for configurable lines */ + if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) + { + assert_param(IS_EXTI_TRIGGER(pExtiConfig->Trigger)); + + /* Configure rising trigger */ + /* Mask or set line */ + if ((pExtiConfig->Trigger & EXTI_TRIGGER_RISING) != 0x00u) + { + EXTI->RTSR |= maskline; + } + else + { + EXTI->RTSR &= ~maskline; + } + + /* Configure falling trigger */ + /* Mask or set line */ + if ((pExtiConfig->Trigger & EXTI_TRIGGER_FALLING) != 0x00u) + { + EXTI->FTSR |= maskline; + } + else + { + EXTI->FTSR &= ~maskline; + } + + + /* Configure gpio port selection in case of gpio exti line */ + if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PORT(pExtiConfig->GPIOSel)); + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = SYSCFG->EXTICR[linepos >> 2u]; + regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + regval |= (pExtiConfig->GPIOSel << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + SYSCFG->EXTICR[linepos >> 2u] = regval; + } + } + + /* Configure interrupt mode : read current mode */ + /* Mask or set line */ + if ((pExtiConfig->Mode & EXTI_MODE_INTERRUPT) != 0x00u) + { + EXTI->IMR |= maskline; + } + else + { + EXTI->IMR &= ~maskline; + } + + /* Configure event mode : read current mode */ + /* Mask or set line */ + if ((pExtiConfig->Mode & EXTI_MODE_EVENT) != 0x00u) + { + EXTI->EMR |= maskline; + } + else + { + EXTI->EMR &= ~maskline; + } + + return HAL_OK; +} + +/** + * @brief Get configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @param pExtiConfig Pointer on structure to store Exti configuration. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if ((hexti == NULL) || (pExtiConfig == NULL)) + { + return HAL_ERROR; + } + + /* Check the parameter */ + assert_param(IS_EXTI_LINE(hexti->Line)); + + /* Store handle line number to configuration structure */ + pExtiConfig->Line = hexti->Line; + + /* Compute line mask */ + linepos = (pExtiConfig->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* 1] Get core mode : interrupt */ + + /* Check if selected line is enable */ + if ((EXTI->IMR & maskline) != 0x00u) + { + pExtiConfig->Mode = EXTI_MODE_INTERRUPT; + } + else + { + pExtiConfig->Mode = EXTI_MODE_NONE; + } + + /* Get event mode */ + /* Check if selected line is enable */ + if ((EXTI->EMR & maskline) != 0x00u) + { + pExtiConfig->Mode |= EXTI_MODE_EVENT; + } + + /* Get default Trigger and GPIOSel configuration */ + pExtiConfig->Trigger = EXTI_TRIGGER_NONE; + pExtiConfig->GPIOSel = 0x00u; + + /* 2] Get trigger for configurable lines : rising */ + if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) + { + /* Check if configuration of selected line is enable */ + if ((EXTI->RTSR & maskline) != 0x00u) + { + pExtiConfig->Trigger = EXTI_TRIGGER_RISING; + } + + /* Get falling configuration */ + /* Check if configuration of selected line is enable */ + if ((EXTI->FTSR & maskline) != 0x00u) + { + pExtiConfig->Trigger |= EXTI_TRIGGER_FALLING; + } + + /* Get Gpio port selection for gpio lines */ + if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = (SYSCFG->EXTICR[linepos >> 2u] << 16u ); + pExtiConfig->GPIOSel = ((regval << (SYSCFG_EXTICR1_EXTI1_Pos * (3uL - (linepos & 0x03u)))) >> 28u); + } + } + + return HAL_OK; +} + +/** + * @brief Clear whole configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if (hexti == NULL) + { + return HAL_ERROR; + } + + /* Check the parameter */ + assert_param(IS_EXTI_LINE(hexti->Line)); + + /* compute line mask */ + linepos = (hexti->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* 1] Clear interrupt mode */ + EXTI->IMR = (EXTI->IMR & ~maskline); + + /* 2] Clear event mode */ + EXTI->EMR = (EXTI->EMR & ~maskline); + + /* 3] Clear triggers in case of configurable lines */ + if ((hexti->Line & EXTI_CONFIG) != 0x00u) + { + EXTI->RTSR = (EXTI->RTSR & ~maskline); + EXTI->FTSR = (EXTI->FTSR & ~maskline); + + /* Get Gpio port selection for gpio lines */ + if ((hexti->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = SYSCFG->EXTICR[linepos >> 2u]; + regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + SYSCFG->EXTICR[linepos >> 2u] = regval; + } + } + + return HAL_OK; +} + +/** + * @brief Register callback for a dedicated Exti line. + * @param hexti Exti handle. + * @param CallbackID User callback identifier. + * This parameter can be one of @arg @ref EXTI_CallbackIDTypeDef values. + * @param pPendingCbfn function pointer to be stored as callback. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)) +{ + HAL_StatusTypeDef status = HAL_OK; + + switch (CallbackID) + { + case HAL_EXTI_COMMON_CB_ID: + hexti->PendingCallback = pPendingCbfn; + break; + + default: + status = HAL_ERROR; + break; + } + + return status; +} + +/** + * @brief Store line number as handle private field. + * @param hexti Exti handle. + * @param ExtiLine Exti line number. + * This parameter can be from 0 to @ref EXTI_LINE_NB. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(ExtiLine)); + + /* Check null pointer */ + if (hexti == NULL) + { + return HAL_ERROR; + } + else + { + /* Store line number as handle private field */ + hexti->Line = ExtiLine; + + return HAL_OK; + } +} + +/** + * @} + */ + +/** @addtogroup EXTI_Exported_Functions_Group2 + * @brief EXTI IO functions. + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Handle EXTI interrupt request. + * @param hexti Exti handle. + * @retval none. + */ +void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti) +{ + uint32_t regval; + uint32_t maskline; + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Get pending bit */ + regval = (EXTI->PR & maskline); + if (regval != 0x00u) + { + /* Clear pending bit */ + EXTI->PR = maskline; + + /* Call callback */ + if (hexti->PendingCallback != NULL) + { + hexti->PendingCallback(); + } + } +} + +/** + * @brief Get interrupt pending bit of a dedicated line. + * @param hexti Exti handle. + * @param Edge Specify which pending edge as to be checked. + * This parameter can be one of the following values: + * @arg @ref EXTI_TRIGGER_RISING_FALLING + * This parameter is kept for compatibility with other series. + * @retval 1 if interrupt is pending else 0. + */ +uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + assert_param(IS_EXTI_PENDING_EDGE(Edge)); + + /* Compute line mask */ + linepos = (hexti->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* return 1 if bit is set else 0 */ + regval = ((EXTI->PR & maskline) >> linepos); + return regval; +} + +/** + * @brief Clear interrupt pending bit of a dedicated line. + * @param hexti Exti handle. + * @param Edge Specify which pending edge as to be clear. + * This parameter can be one of the following values: + * @arg @ref EXTI_TRIGGER_RISING_FALLING + * This parameter is kept for compatibility with other series. + * @retval None. + */ +void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) +{ + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + assert_param(IS_EXTI_PENDING_EDGE(Edge)); + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Clear Pending bit */ + EXTI->PR = maskline; +} + +/** + * @brief Generate a software interrupt for a dedicated line. + * @param hexti Exti handle. + * @retval None. + */ +void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti) +{ + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Generate Software interrupt */ + EXTI->SWIER = maskline; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_EXTI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c index 2830da0..d18f66f 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c @@ -1,775 +1,775 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash.c - * @author MCD Application Team - * @brief FLASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the internal FLASH memory: - * + Program operations functions - * + Memory Control functions - * + Peripheral Errors functions - * - @verbatim - ============================================================================== - ##### FLASH peripheral features ##### - ============================================================================== - - [..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses - to the Flash memory. It implements the erase and program Flash memory operations - and the read and write protection mechanisms. - - [..] The Flash memory interface accelerates code execution with a system of instruction - prefetch and cache lines. - - [..] The FLASH main features are: - (+) Flash memory read operations - (+) Flash memory program/erase operations - (+) Read / write protections - (+) Prefetch on I-Code - (+) 64 cache lines of 128 bits on I-Code - (+) 8 cache lines of 128 bits on D-Code - - - ##### How to use this driver ##### - ============================================================================== - [..] - This driver provides functions and macros to configure and program the FLASH - memory of all STM32F4xx devices. - - (#) FLASH Memory IO Programming functions: - (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and - HAL_FLASH_Lock() functions - (++) Program functions: byte, half word, word and double word - (++) There Two modes of programming : - (+++) Polling mode using HAL_FLASH_Program() function - (+++) Interrupt mode using HAL_FLASH_Program_IT() function - - (#) Interrupts and flags management functions : - (++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler() - (++) Wait for last FLASH operation according to its status - (++) Get error flag status by calling HAL_SetErrorCode() - - [..] - In addition to these functions, this driver includes a set of macros allowing - to handle the following operations: - (+) Set the latency - (+) Enable/Disable the prefetch buffer - (+) Enable/Disable the Instruction cache and the Data cache - (+) Reset the Instruction cache and the Data cache - (+) Enable/Disable the FLASH interrupts - (+) Monitor the FLASH flags status - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASH FLASH - * @brief FLASH HAL module driver - * @{ - */ - -#ifdef HAL_FLASH_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup FLASH_Private_Constants - * @{ - */ -#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup FLASH_Private_Variables - * @{ - */ -/* Variable used for Erase sectors under interruption */ -FLASH_ProcessTypeDef pFlash; -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup FLASH_Private_Functions - * @{ - */ -/* Program operations */ -static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data); -static void FLASH_Program_Word(uint32_t Address, uint32_t Data); -static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data); -static void FLASH_Program_Byte(uint32_t Address, uint8_t Data); -static void FLASH_SetErrorCode(void); - -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Functions FLASH Exported Functions - * @{ - */ - -/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions - * @brief Programming operation functions - * -@verbatim - =============================================================================== - ##### Programming operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the FLASH - program operations. - -@endverbatim - * @{ - */ - -/** - * @brief Program byte, halfword, word or double word at a specified address - * @param TypeProgram Indicate the way to program at a specified address. - * This parameter can be a value of @ref FLASH_Type_Program - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed - * - * @retval HAL_StatusTypeDef HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if(status == HAL_OK) - { - if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) - { - /*Program byte (8-bit) at a specified address.*/ - FLASH_Program_Byte(Address, (uint8_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) - { - /*Program halfword (16-bit) at a specified address.*/ - FLASH_Program_HalfWord(Address, (uint16_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) - { - /*Program word (32-bit) at a specified address.*/ - FLASH_Program_Word(Address, (uint32_t) Data); - } - else - { - /*Program double word (64-bit) at a specified address.*/ - FLASH_Program_DoubleWord(Address, Data); - } - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* If the program operation is completed, disable the PG Bit */ - FLASH->CR &= (~FLASH_CR_PG); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Program byte, halfword, word or double word at a specified address with interrupt enabled. - * @param TypeProgram Indicate the way to program at a specified address. - * This parameter can be a value of @ref FLASH_Type_Program - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); - - /* Enable End of FLASH Operation interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); - - /* Enable Error source interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); - - pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM; - pFlash.Address = Address; - - if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) - { - /*Program byte (8-bit) at a specified address.*/ - FLASH_Program_Byte(Address, (uint8_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) - { - /*Program halfword (16-bit) at a specified address.*/ - FLASH_Program_HalfWord(Address, (uint16_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) - { - /*Program word (32-bit) at a specified address.*/ - FLASH_Program_Word(Address, (uint32_t) Data); - } - else - { - /*Program double word (64-bit) at a specified address.*/ - FLASH_Program_DoubleWord(Address, Data); - } - - return status; -} - -/** - * @brief This function handles FLASH interrupt request. - * @retval None - */ -void HAL_FLASH_IRQHandler(void) -{ - uint32_t addresstmp = 0U; - - /* Check FLASH operation error flags */ -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) -#else - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) -#endif /* FLASH_SR_RDERR */ - { - if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) - { - /*return the faulty sector*/ - addresstmp = pFlash.Sector; - pFlash.Sector = 0xFFFFFFFFU; - } - else if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) - { - /*return the faulty bank*/ - addresstmp = pFlash.Bank; - } - else - { - /*return the faulty address*/ - addresstmp = pFlash.Address; - } - - /*Save the Error code*/ - FLASH_SetErrorCode(); - - /* FLASH error interrupt user callback */ - HAL_FLASH_OperationErrorCallback(addresstmp); - - /*Stop the procedure ongoing*/ - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - } - - /* Check FLASH End of Operation flag */ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) - { - /* Clear FLASH End of Operation pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); - - if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) - { - /*Nb of sector to erased can be decreased*/ - pFlash.NbSectorsToErase--; - - /* Check if there are still sectors to erase*/ - if(pFlash.NbSectorsToErase != 0U) - { - addresstmp = pFlash.Sector; - /*Indicate user which sector has been erased*/ - HAL_FLASH_EndOfOperationCallback(addresstmp); - - /*Increment sector number*/ - pFlash.Sector++; - addresstmp = pFlash.Sector; - FLASH_Erase_Sector(addresstmp, pFlash.VoltageForErase); - } - else - { - /*No more sectors to Erase, user callback can be called.*/ - /*Reset Sector and stop Erase sectors procedure*/ - pFlash.Sector = addresstmp = 0xFFFFFFFFU; - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches() ; - - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(addresstmp); - } - } - else - { - if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) - { - /* MassErase ended. Return the selected bank */ - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches() ; - - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(pFlash.Bank); - } - else - { - /*Program ended. Return the selected address*/ - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(pFlash.Address); - } - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - } - } - - if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE) - { - /* Operation is completed, disable the PG, SER, SNB and MER Bits */ - CLEAR_BIT(FLASH->CR, (FLASH_CR_PG | FLASH_CR_SER | FLASH_CR_SNB | FLASH_MER_BIT)); - - /* Disable End of FLASH Operation interrupt */ - __HAL_FLASH_DISABLE_IT(FLASH_IT_EOP); - - /* Disable Error source interrupt */ - __HAL_FLASH_DISABLE_IT(FLASH_IT_ERR); - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - } -} - -/** - * @brief FLASH end of operation interrupt callback - * @param ReturnValue The value saved in this parameter depends on the ongoing procedure - * Mass Erase: Bank number which has been requested to erase - * Sectors Erase: Sector which has been erased - * (if 0xFFFFFFFFU, it means that all the selected sectors have been erased) - * Program: Address which was selected for data program - * @retval None - */ -__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(ReturnValue); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_FLASH_EndOfOperationCallback could be implemented in the user file - */ -} - -/** - * @brief FLASH operation error interrupt callback - * @param ReturnValue The value saved in this parameter depends on the ongoing procedure - * Mass Erase: Bank number which has been requested to erase - * Sectors Erase: Sector number which returned an error - * Program: Address which was selected for data program - * @retval None - */ -__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(ReturnValue); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_FLASH_OperationErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions - * @brief management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the FLASH - memory operations. - -@endverbatim - * @{ - */ - -/** - * @brief Unlock the FLASH control register access - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Unlock(void) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) - { - /* Authorize the FLASH Registers access */ - WRITE_REG(FLASH->KEYR, FLASH_KEY1); - WRITE_REG(FLASH->KEYR, FLASH_KEY2); - - /* Verify Flash is unlocked */ - if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) - { - status = HAL_ERROR; - } - } - - return status; -} - -/** - * @brief Locks the FLASH control register access - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Lock(void) -{ - /* Set the LOCK Bit to lock the FLASH Registers access */ - FLASH->CR |= FLASH_CR_LOCK; - - return HAL_OK; -} - -/** - * @brief Unlock the FLASH Option Control Registers access. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void) -{ - if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET) - { - /* Authorizes the Option Byte register programming */ - FLASH->OPTKEYR = FLASH_OPT_KEY1; - FLASH->OPTKEYR = FLASH_OPT_KEY2; - } - else - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Lock the FLASH Option Control Registers access. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Lock(void) -{ - /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */ - FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; - - return HAL_OK; -} - -/** - * @brief Launch the option byte loading. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Launch(void) -{ - /* Set the OPTSTRT bit in OPTCR register */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT; - - /* Wait for last operation to be completed */ - return(FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE)); -} - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief Peripheral Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral Errors functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time Errors of the FLASH peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Get the specific FLASH error flag. - * @retval FLASH_ErrorCode: The returned value can be a combination of: - * @arg HAL_FLASH_ERROR_RD: FLASH Read Protection error flag (PCROP) - * @arg HAL_FLASH_ERROR_PGS: FLASH Programming Sequence error flag - * @arg HAL_FLASH_ERROR_PGP: FLASH Programming Parallelism error flag - * @arg HAL_FLASH_ERROR_PGA: FLASH Programming Alignment error flag - * @arg HAL_FLASH_ERROR_WRP: FLASH Write protected error flag - * @arg HAL_FLASH_ERROR_OPERATION: FLASH operation Error flag - */ -uint32_t HAL_FLASH_GetError(void) -{ - return pFlash.ErrorCode; -} - -/** - * @} - */ - -/** - * @brief Wait for a FLASH operation to complete. - * @param Timeout maximum flash operationtimeout - * @retval HAL Status - */ -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Clear Error Code */ - pFlash.ErrorCode = HAL_FLASH_ERROR_NONE; - - /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset. - Even if the FLASH operation fails, the BUSY flag will be reset and an error - flag will be set */ - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY) != RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - /* Check FLASH End of Operation flag */ - if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) - { - /* Clear FLASH End of Operation pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); - } -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) -#else - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) -#endif /* FLASH_SR_RDERR */ - { - /*Save the error code*/ - FLASH_SetErrorCode(); - return HAL_ERROR; - } - - /* If there is no error flag set */ - return HAL_OK; - -} - -/** - * @brief Program a double word (64-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.7V to 3.6V and Vpp in the range 7V to 9V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD; - FLASH->CR |= FLASH_CR_PG; - - /* Program first word */ - *(__IO uint32_t*)Address = (uint32_t)Data; - - /* Barrier to ensure programming is performed in 2 steps, in right order - (independently of compiler optimization behavior) */ - __ISB(); - - /* Program second word */ - *(__IO uint32_t*)(Address+4) = (uint32_t)(Data >> 32); -} - - -/** - * @brief Program word (32-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.7V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_Word(uint32_t Address, uint32_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_WORD; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint32_t*)Address = Data; -} - -/** - * @brief Program a half-word (16-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.1V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_HALF_WORD; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint16_t*)Address = Data; -} - -/** - * @brief Program byte (8-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 1.8V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_Byte(uint32_t Address, uint8_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_BYTE; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint8_t*)Address = Data; -} - -/** - * @brief Set the specific FLASH error flag. - * @retval None - */ -static void FLASH_SetErrorCode(void) -{ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP; - - /* Clear FLASH write protection error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_WRPERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGA; - - /* Clear FLASH Programming alignment error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGAERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGP; - - /* Clear FLASH Programming parallelism error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGPERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGSERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGS; - - /* Clear FLASH Programming sequence error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGSERR); - } -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_RD; - - /* Clear FLASH Proprietary readout protection error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_RDERR); - } -#endif /* FLASH_SR_RDERR */ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_OPERATION; - - /* Clear FLASH Operation error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR); - } -} - -/** - * @} - */ - -#endif /* HAL_FLASH_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash.c + * @author MCD Application Team + * @brief FLASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the internal FLASH memory: + * + Program operations functions + * + Memory Control functions + * + Peripheral Errors functions + * + @verbatim + ============================================================================== + ##### FLASH peripheral features ##### + ============================================================================== + + [..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses + to the Flash memory. It implements the erase and program Flash memory operations + and the read and write protection mechanisms. + + [..] The Flash memory interface accelerates code execution with a system of instruction + prefetch and cache lines. + + [..] The FLASH main features are: + (+) Flash memory read operations + (+) Flash memory program/erase operations + (+) Read / write protections + (+) Prefetch on I-Code + (+) 64 cache lines of 128 bits on I-Code + (+) 8 cache lines of 128 bits on D-Code + + + ##### How to use this driver ##### + ============================================================================== + [..] + This driver provides functions and macros to configure and program the FLASH + memory of all STM32F4xx devices. + + (#) FLASH Memory IO Programming functions: + (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and + HAL_FLASH_Lock() functions + (++) Program functions: byte, half word, word and double word + (++) There Two modes of programming : + (+++) Polling mode using HAL_FLASH_Program() function + (+++) Interrupt mode using HAL_FLASH_Program_IT() function + + (#) Interrupts and flags management functions : + (++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler() + (++) Wait for last FLASH operation according to its status + (++) Get error flag status by calling HAL_SetErrorCode() + + [..] + In addition to these functions, this driver includes a set of macros allowing + to handle the following operations: + (+) Set the latency + (+) Enable/Disable the prefetch buffer + (+) Enable/Disable the Instruction cache and the Data cache + (+) Reset the Instruction cache and the Data cache + (+) Enable/Disable the FLASH interrupts + (+) Monitor the FLASH flags status + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASH FLASH + * @brief FLASH HAL module driver + * @{ + */ + +#ifdef HAL_FLASH_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup FLASH_Private_Constants + * @{ + */ +#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup FLASH_Private_Variables + * @{ + */ +/* Variable used for Erase sectors under interruption */ +FLASH_ProcessTypeDef pFlash; +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup FLASH_Private_Functions + * @{ + */ +/* Program operations */ +static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data); +static void FLASH_Program_Word(uint32_t Address, uint32_t Data); +static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data); +static void FLASH_Program_Byte(uint32_t Address, uint8_t Data); +static void FLASH_SetErrorCode(void); + +HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASH_Exported_Functions FLASH Exported Functions + * @{ + */ + +/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions + * @brief Programming operation functions + * +@verbatim + =============================================================================== + ##### Programming operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the FLASH + program operations. + +@endverbatim + * @{ + */ + +/** + * @brief Program byte, halfword, word or double word at a specified address + * @param TypeProgram Indicate the way to program at a specified address. + * This parameter can be a value of @ref FLASH_Type_Program + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed + * + * @retval HAL_StatusTypeDef HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if(status == HAL_OK) + { + if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) + { + /*Program byte (8-bit) at a specified address.*/ + FLASH_Program_Byte(Address, (uint8_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) + { + /*Program halfword (16-bit) at a specified address.*/ + FLASH_Program_HalfWord(Address, (uint16_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) + { + /*Program word (32-bit) at a specified address.*/ + FLASH_Program_Word(Address, (uint32_t) Data); + } + else + { + /*Program double word (64-bit) at a specified address.*/ + FLASH_Program_DoubleWord(Address, Data); + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* If the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Program byte, halfword, word or double word at a specified address with interrupt enabled. + * @param TypeProgram Indicate the way to program at a specified address. + * This parameter can be a value of @ref FLASH_Type_Program + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); + + /* Enable End of FLASH Operation interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); + + /* Enable Error source interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); + + pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM; + pFlash.Address = Address; + + if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) + { + /*Program byte (8-bit) at a specified address.*/ + FLASH_Program_Byte(Address, (uint8_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) + { + /*Program halfword (16-bit) at a specified address.*/ + FLASH_Program_HalfWord(Address, (uint16_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) + { + /*Program word (32-bit) at a specified address.*/ + FLASH_Program_Word(Address, (uint32_t) Data); + } + else + { + /*Program double word (64-bit) at a specified address.*/ + FLASH_Program_DoubleWord(Address, Data); + } + + return status; +} + +/** + * @brief This function handles FLASH interrupt request. + * @retval None + */ +void HAL_FLASH_IRQHandler(void) +{ + uint32_t addresstmp = 0U; + + /* Check FLASH operation error flags */ +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) +#else + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) +#endif /* FLASH_SR_RDERR */ + { + if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) + { + /*return the faulty sector*/ + addresstmp = pFlash.Sector; + pFlash.Sector = 0xFFFFFFFFU; + } + else if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) + { + /*return the faulty bank*/ + addresstmp = pFlash.Bank; + } + else + { + /*return the faulty address*/ + addresstmp = pFlash.Address; + } + + /*Save the Error code*/ + FLASH_SetErrorCode(); + + /* FLASH error interrupt user callback */ + HAL_FLASH_OperationErrorCallback(addresstmp); + + /*Stop the procedure ongoing*/ + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + } + + /* Check FLASH End of Operation flag */ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) + { + /* Clear FLASH End of Operation pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); + + if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) + { + /*Nb of sector to erased can be decreased*/ + pFlash.NbSectorsToErase--; + + /* Check if there are still sectors to erase*/ + if(pFlash.NbSectorsToErase != 0U) + { + addresstmp = pFlash.Sector; + /*Indicate user which sector has been erased*/ + HAL_FLASH_EndOfOperationCallback(addresstmp); + + /*Increment sector number*/ + pFlash.Sector++; + addresstmp = pFlash.Sector; + FLASH_Erase_Sector(addresstmp, pFlash.VoltageForErase); + } + else + { + /*No more sectors to Erase, user callback can be called.*/ + /*Reset Sector and stop Erase sectors procedure*/ + pFlash.Sector = addresstmp = 0xFFFFFFFFU; + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches() ; + + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(addresstmp); + } + } + else + { + if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) + { + /* MassErase ended. Return the selected bank */ + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches() ; + + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(pFlash.Bank); + } + else + { + /*Program ended. Return the selected address*/ + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(pFlash.Address); + } + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + } + } + + if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE) + { + /* Operation is completed, disable the PG, SER, SNB and MER Bits */ + CLEAR_BIT(FLASH->CR, (FLASH_CR_PG | FLASH_CR_SER | FLASH_CR_SNB | FLASH_MER_BIT)); + + /* Disable End of FLASH Operation interrupt */ + __HAL_FLASH_DISABLE_IT(FLASH_IT_EOP); + + /* Disable Error source interrupt */ + __HAL_FLASH_DISABLE_IT(FLASH_IT_ERR); + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + } +} + +/** + * @brief FLASH end of operation interrupt callback + * @param ReturnValue The value saved in this parameter depends on the ongoing procedure + * Mass Erase: Bank number which has been requested to erase + * Sectors Erase: Sector which has been erased + * (if 0xFFFFFFFFU, it means that all the selected sectors have been erased) + * Program: Address which was selected for data program + * @retval None + */ +__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(ReturnValue); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_FLASH_EndOfOperationCallback could be implemented in the user file + */ +} + +/** + * @brief FLASH operation error interrupt callback + * @param ReturnValue The value saved in this parameter depends on the ongoing procedure + * Mass Erase: Bank number which has been requested to erase + * Sectors Erase: Sector number which returned an error + * Program: Address which was selected for data program + * @retval None + */ +__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(ReturnValue); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_FLASH_OperationErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the FLASH + memory operations. + +@endverbatim + * @{ + */ + +/** + * @brief Unlock the FLASH control register access + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Unlock(void) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) + { + /* Authorize the FLASH Registers access */ + WRITE_REG(FLASH->KEYR, FLASH_KEY1); + WRITE_REG(FLASH->KEYR, FLASH_KEY2); + + /* Verify Flash is unlocked */ + if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) + { + status = HAL_ERROR; + } + } + + return status; +} + +/** + * @brief Locks the FLASH control register access + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Lock(void) +{ + /* Set the LOCK Bit to lock the FLASH Registers access */ + FLASH->CR |= FLASH_CR_LOCK; + + return HAL_OK; +} + +/** + * @brief Unlock the FLASH Option Control Registers access. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void) +{ + if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET) + { + /* Authorizes the Option Byte register programming */ + FLASH->OPTKEYR = FLASH_OPT_KEY1; + FLASH->OPTKEYR = FLASH_OPT_KEY2; + } + else + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Lock the FLASH Option Control Registers access. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Lock(void) +{ + /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */ + FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; + + return HAL_OK; +} + +/** + * @brief Launch the option byte loading. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Launch(void) +{ + /* Set the OPTSTRT bit in OPTCR register */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT; + + /* Wait for last operation to be completed */ + return(FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE)); +} + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief Peripheral Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral Errors functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time Errors of the FLASH peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Get the specific FLASH error flag. + * @retval FLASH_ErrorCode: The returned value can be a combination of: + * @arg HAL_FLASH_ERROR_RD: FLASH Read Protection error flag (PCROP) + * @arg HAL_FLASH_ERROR_PGS: FLASH Programming Sequence error flag + * @arg HAL_FLASH_ERROR_PGP: FLASH Programming Parallelism error flag + * @arg HAL_FLASH_ERROR_PGA: FLASH Programming Alignment error flag + * @arg HAL_FLASH_ERROR_WRP: FLASH Write protected error flag + * @arg HAL_FLASH_ERROR_OPERATION: FLASH operation Error flag + */ +uint32_t HAL_FLASH_GetError(void) +{ + return pFlash.ErrorCode; +} + +/** + * @} + */ + +/** + * @brief Wait for a FLASH operation to complete. + * @param Timeout maximum flash operationtimeout + * @retval HAL Status + */ +HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Clear Error Code */ + pFlash.ErrorCode = HAL_FLASH_ERROR_NONE; + + /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset. + Even if the FLASH operation fails, the BUSY flag will be reset and an error + flag will be set */ + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY) != RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + /* Check FLASH End of Operation flag */ + if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) + { + /* Clear FLASH End of Operation pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); + } +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) +#else + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) +#endif /* FLASH_SR_RDERR */ + { + /*Save the error code*/ + FLASH_SetErrorCode(); + return HAL_ERROR; + } + + /* If there is no error flag set */ + return HAL_OK; + +} + +/** + * @brief Program a double word (64-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.7V to 3.6V and Vpp in the range 7V to 9V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD; + FLASH->CR |= FLASH_CR_PG; + + /* Program first word */ + *(__IO uint32_t*)Address = (uint32_t)Data; + + /* Barrier to ensure programming is performed in 2 steps, in right order + (independently of compiler optimization behavior) */ + __ISB(); + + /* Program second word */ + *(__IO uint32_t*)(Address+4) = (uint32_t)(Data >> 32); +} + + +/** + * @brief Program word (32-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.7V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_Word(uint32_t Address, uint32_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint32_t*)Address = Data; +} + +/** + * @brief Program a half-word (16-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.1V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_HALF_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint16_t*)Address = Data; +} + +/** + * @brief Program byte (8-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 1.8V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_Byte(uint32_t Address, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_BYTE; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint8_t*)Address = Data; +} + +/** + * @brief Set the specific FLASH error flag. + * @retval None + */ +static void FLASH_SetErrorCode(void) +{ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP; + + /* Clear FLASH write protection error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_WRPERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGA; + + /* Clear FLASH Programming alignment error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGAERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGP; + + /* Clear FLASH Programming parallelism error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGPERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGSERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGS; + + /* Clear FLASH Programming sequence error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGSERR); + } +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_RD; + + /* Clear FLASH Proprietary readout protection error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_RDERR); + } +#endif /* FLASH_SR_RDERR */ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_OPERATION; + + /* Clear FLASH Operation error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR); + } +} + +/** + * @} + */ + +#endif /* HAL_FLASH_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c index d99eace..abff6d7 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c @@ -1,1347 +1,1347 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ex.c - * @author MCD Application Team - * @brief Extended FLASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the FLASH extension peripheral: - * + Extended programming operations functions - * - @verbatim - ============================================================================== - ##### Flash Extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the FLASH interface for STM32F427xx/437xx and - STM32F429xx/439xx devices contains the following additional features - - (+) Capacity up to 2 Mbyte with dual bank architecture supporting read-while-write - capability (RWW) - (+) Dual bank memory organization - (+) PCROP protection for all banks - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to configure and program the FLASH memory - of all STM32F427xx/437xx, STM32F429xx/439xx, STM32F469xx/479xx and STM32F446xx - devices. It includes - (#) FLASH Memory Erase functions: - (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and - HAL_FLASH_Lock() functions - (++) Erase function: Erase sector, erase all sectors - (++) There are two modes of erase : - (+++) Polling Mode using HAL_FLASHEx_Erase() - (+++) Interrupt Mode using HAL_FLASHEx_Erase_IT() - - (#) Option Bytes Programming functions: Use HAL_FLASHEx_OBProgram() to : - (++) Set/Reset the write protection - (++) Set the Read protection Level - (++) Set the BOR level - (++) Program the user Option Bytes - (#) Advanced Option Bytes Programming functions: Use HAL_FLASHEx_AdvOBProgram() to : - (++) Extended space (bank 2) erase function - (++) Full FLASH space (2 Mo) erase (bank 1 and bank 2) - (++) Dual Boot activation - (++) Write protection configuration for bank 2 - (++) PCROP protection configuration and control for both banks - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASHEx FLASHEx - * @brief FLASH HAL Extension module driver - * @{ - */ - -#ifdef HAL_FLASH_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Constants - * @{ - */ -#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Variables - * @{ - */ -extern FLASH_ProcessTypeDef pFlash; -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Functions - * @{ - */ -/* Option bytes control */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level); -static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby); -static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level); -static uint8_t FLASH_OB_GetUser(void); -static uint16_t FLASH_OB_GetWRP(void); -static uint8_t FLASH_OB_GetRDP(void); -static uint8_t FLASH_OB_GetBOR(void); - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector); -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -extern HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASHEx_Exported_Functions FLASHEx Exported Functions - * @{ - */ - -/** @defgroup FLASHEx_Exported_Functions_Group1 Extended IO operation functions - * @brief Extended IO operation functions - * -@verbatim - =============================================================================== - ##### Extended programming operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the Extension FLASH - programming operations. - -@endverbatim - * @{ - */ -/** - * @brief Perform a mass erase or erase the specified FLASH memory sectors - * @param[in] pEraseInit pointer to an FLASH_EraseInitTypeDef structure that - * contains the configuration information for the erasing. - * - * @param[out] SectorError pointer to variable that - * contains the configuration information on faulty sector in case of error - * (0xFFFFFFFFU means that all the sectors have been correctly erased) - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *SectorError) -{ - HAL_StatusTypeDef status = HAL_ERROR; - uint32_t index = 0U; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Initialization of SectorError variable*/ - *SectorError = 0xFFFFFFFFU; - - if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) - { - /*Mass erase to be done*/ - FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* if the erase operation is completed, disable the MER Bit */ - FLASH->CR &= (~FLASH_MER_BIT); - } - else - { - /* Check the parameters */ - assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); - - /* Erase by sector by sector to be done*/ - for (index = pEraseInit->Sector; index < (pEraseInit->NbSectors + pEraseInit->Sector); index++) - { - FLASH_Erase_Sector(index, (uint8_t) pEraseInit->VoltageRange); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* If the erase operation is completed, disable the SER and SNB Bits */ - CLEAR_BIT(FLASH->CR, (FLASH_CR_SER | FLASH_CR_SNB)); - - if (status != HAL_OK) - { - /* In case of error, stop erase procedure and return the faulty sector*/ - *SectorError = index; - break; - } - } - } - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches(); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Perform a mass erase or erase the specified FLASH memory sectors with interrupt enabled - * @param pEraseInit pointer to an FLASH_EraseInitTypeDef structure that - * contains the configuration information for the erasing. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); - - /* Enable End of FLASH Operation interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); - - /* Enable Error source interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); - - /* Clear pending flags (if any) */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \ - FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - - if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) - { - /*Mass erase to be done*/ - pFlash.ProcedureOnGoing = FLASH_PROC_MASSERASE; - pFlash.Bank = pEraseInit->Banks; - FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); - } - else - { - /* Erase by sector to be done*/ - - /* Check the parameters */ - assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); - - pFlash.ProcedureOnGoing = FLASH_PROC_SECTERASE; - pFlash.NbSectorsToErase = pEraseInit->NbSectors; - pFlash.Sector = pEraseInit->Sector; - pFlash.VoltageForErase = (uint8_t)pEraseInit->VoltageRange; - - /*Erase 1st sector and wait for IT*/ - FLASH_Erase_Sector(pEraseInit->Sector, pEraseInit->VoltageRange); - } - - return status; -} - -/** - * @brief Program option bytes - * @param pOBInit pointer to an FLASH_OBInitStruct structure that - * contains the configuration information for the programming. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_OPTIONBYTE(pOBInit->OptionType)); - - /*Write protection configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_WRP) == OPTIONBYTE_WRP) - { - assert_param(IS_WRPSTATE(pOBInit->WRPState)); - if (pOBInit->WRPState == OB_WRPSTATE_ENABLE) - { - /*Enable of Write protection on the selected Sector*/ - status = FLASH_OB_EnableWRP(pOBInit->WRPSector, pOBInit->Banks); - } - else - { - /*Disable of Write protection on the selected Sector*/ - status = FLASH_OB_DisableWRP(pOBInit->WRPSector, pOBInit->Banks); - } - } - - /*Read protection configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_RDP) == OPTIONBYTE_RDP) - { - status = FLASH_OB_RDP_LevelConfig(pOBInit->RDPLevel); - } - - /*USER configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_USER) == OPTIONBYTE_USER) - { - status = FLASH_OB_UserConfig(pOBInit->USERConfig & OB_IWDG_SW, - pOBInit->USERConfig & OB_STOP_NO_RST, - pOBInit->USERConfig & OB_STDBY_NO_RST); - } - - /*BOR Level configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_BOR) == OPTIONBYTE_BOR) - { - status = FLASH_OB_BOR_LevelConfig(pOBInit->BORLevel); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Get the Option byte configuration - * @param pOBInit pointer to an FLASH_OBInitStruct structure that - * contains the configuration information for the programming. - * - * @retval None - */ -void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit) -{ - pOBInit->OptionType = OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER | OPTIONBYTE_BOR; - - /*Get WRP*/ - pOBInit->WRPSector = (uint32_t)FLASH_OB_GetWRP(); - - /*Get RDP Level*/ - pOBInit->RDPLevel = (uint32_t)FLASH_OB_GetRDP(); - - /*Get USER*/ - pOBInit->USERConfig = (uint8_t)FLASH_OB_GetUser(); - - /*Get BOR Level*/ - pOBInit->BORLevel = (uint32_t)FLASH_OB_GetBOR(); -} - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Program option bytes - * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that - * contains the configuration information for the programming. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_AdvOBProgram(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Check the parameters */ - assert_param(IS_OBEX(pAdvOBInit->OptionType)); - - /*Program PCROP option byte*/ - if (((pAdvOBInit->OptionType) & OPTIONBYTE_PCROP) == OPTIONBYTE_PCROP) - { - /* Check the parameters */ - assert_param(IS_PCROPSTATE(pAdvOBInit->PCROPState)); - if ((pAdvOBInit->PCROPState) == OB_PCROP_STATE_ENABLE) - { - /*Enable of Write protection on the selected Sector*/ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - status = FLASH_OB_EnablePCROP(pAdvOBInit->Sectors); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - status = FLASH_OB_EnablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - } - else - { - /*Disable of Write protection on the selected Sector*/ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - status = FLASH_OB_DisablePCROP(pAdvOBInit->Sectors); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - status = FLASH_OB_DisablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - } - } - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - /*Program BOOT config option byte*/ - if (((pAdvOBInit->OptionType) & OPTIONBYTE_BOOTCONFIG) == OPTIONBYTE_BOOTCONFIG) - { - status = FLASH_OB_BootConfig(pAdvOBInit->BootConfig); - } -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - - return status; -} - -/** - * @brief Get the OBEX byte configuration - * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that - * contains the configuration information for the programming. - * - * @retval None - */ -void HAL_FLASHEx_AdvOBGetConfig(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) -{ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /*Get Sector*/ - pAdvOBInit->Sectors = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - /*Get Sector for Bank1*/ - pAdvOBInit->SectorsBank1 = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); - - /*Get Sector for Bank2*/ - pAdvOBInit->SectorsBank2 = (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); - - /*Get Boot config OB*/ - pAdvOBInit->BootConfig = *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS; -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ -} - -/** - * @brief Select the Protection Mode - * - * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted - * Global Read Out Protection modification (from level1 to level0) - * @note Once SPRMOD bit is active unprotection of a protected sector is not possible - * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ - * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OB_SelectPCROP(void) -{ - uint8_t optiontmp = 0xFF; - - /* Mask SPRMOD bit */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); - - /* Update Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_SELECTED | optiontmp); - - return HAL_OK; -} - -/** - * @brief Deselect the Protection Mode - * - * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted - * Global Read Out Protection modification (from level1 to level0) - * @note Once SPRMOD bit is active unprotection of a protected sector is not possible - * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ - * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OB_DeSelectPCROP(void) -{ - uint8_t optiontmp = 0xFF; - - /* Mask SPRMOD bit */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); - - /* Update Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_DESELECTED | optiontmp); - - return HAL_OK; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx ||\ - STM32F411xE || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Returns the FLASH Write Protection Option Bytes value for Bank 2 - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx devices. - * @retval The FLASH Write Protection Option Bytes value - */ -uint16_t HAL_FLASHEx_OB_GetBank2WRP(void) -{ - /* Return the FLASH write protection Register value */ - return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Full erase of FLASH memory sectors - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @param Banks Banks to be erased - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * @arg FLASH_BANK_2: Bank2 to be erased - * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased - * - * @retval HAL Status - */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) -{ - /* Check the parameters */ - assert_param(IS_VOLTAGERANGE(VoltageRange)); - assert_param(IS_FLASH_BANK(Banks)); - - /* if the previous operation is completed, proceed to erase all sectors */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - - if (Banks == FLASH_BANK_BOTH) - { - /* bank1 & bank2 will be erased*/ - FLASH->CR |= FLASH_MER_BIT; - } - else if (Banks == FLASH_BANK_1) - { - /*Only bank1 will be erased*/ - FLASH->CR |= FLASH_CR_MER1; - } - else - { - /*Only bank2 will be erased*/ - FLASH->CR |= FLASH_CR_MER2; - } - FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); -} - -/** - * @brief Erase the specified FLASH memory sector - * @param Sector FLASH sector to erase - * The value of this parameter depend on device used within the same series - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @retval None - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) -{ - uint32_t tmp_psize = 0U; - - /* Check the parameters */ - assert_param(IS_FLASH_SECTOR(Sector)); - assert_param(IS_VOLTAGERANGE(VoltageRange)); - - if (VoltageRange == FLASH_VOLTAGE_RANGE_1) - { - tmp_psize = FLASH_PSIZE_BYTE; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) - { - tmp_psize = FLASH_PSIZE_HALF_WORD; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) - { - tmp_psize = FLASH_PSIZE_WORD; - } - else - { - tmp_psize = FLASH_PSIZE_DOUBLE_WORD; - } - - /* Need to add offset of 4 when sector higher than FLASH_SECTOR_11 */ - if (Sector > FLASH_SECTOR_11) - { - Sector += 4U; - } - /* If the previous operation is completed, proceed to erase the sector */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= tmp_psize; - CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); - FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); - FLASH->CR |= FLASH_CR_STRT; -} - -/** - * @brief Enable the write protection of the desired bank1 or bank 2 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * This parameter can be one of the following values: - * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 - * @arg OB_WRP_SECTOR_All - * @note BANK2 starts from OB_WRP_SECTOR_12 - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL FLASH State - */ -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || - (WRPSector < OB_WRP_SECTOR_12)) - { - if (WRPSector == OB_WRP_SECTOR_All) - { - /*Write protection on all sector of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - else - { - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); - } - } - else - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - - /*Write protection on all sector of BANK2*/ - if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - } - - } - return status; -} - -/** - * @brief Disable the write protection of the desired bank1 or bank 2 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * This parameter can be one of the following values: - * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 - * @arg OB_WRP_Sector_All - * @note BANK2 starts from OB_WRP_SECTOR_12 - * - * @param Banks Disable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * @arg FLASH_BANK_2: Bank2 to be erased - * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || - (WRPSector < OB_WRP_SECTOR_12)) - { - if (WRPSector == OB_WRP_SECTOR_All) - { - /*Write protection on all sector of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - else - { - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; - } - } - else - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - - /*Write protection on all sector of BANK2*/ - if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - } - - } - - return status; -} - -/** - * @brief Configure the Dual Bank Boot. - * - * @note This function can be used only for STM32F42xxx/43xxx devices. - * - * @param BootConfig specifies the Dual Bank Boot Option byte. - * This parameter can be one of the following values: - * @arg OB_Dual_BootEnabled: Dual Bank Boot Enable - * @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled - * @retval None - */ -static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_BOOT(BootConfig)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /* Set Dual Bank Boot */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2); - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= BootConfig; - } - - return status; -} - -/** - * @brief Enable the read/write protection (PCROP) of the desired - * sectors of Bank 1 and/or Bank 2. - * @note This function can be used only for STM32F42xxx/43xxx devices. - * @param SectorBank1 Specifies the sector(s) to be read/write protected or unprotected for bank1. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 - * @arg OB_PCROP_SECTOR__All - * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 - * @arg OB_PCROP_SECTOR__All - * @param Banks Enable PCROP protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) - { - assert_param(IS_OB_PCROP(SectorBank1)); - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)SectorBank1; - } - else - { - assert_param(IS_OB_PCROP(SectorBank2)); - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; - } - - /*Write protection on all sector of BANK2*/ - if (Banks == FLASH_BANK_BOTH) - { - assert_param(IS_OB_PCROP(SectorBank2)); - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; - } - } - - } - - return status; -} - - -/** - * @brief Disable the read/write protection (PCROP) of the desired - * sectors of Bank 1 and/or Bank 2. - * @note This function can be used only for STM32F42xxx/43xxx devices. - * @param SectorBank1 specifies the sector(s) to be read/write protected or unprotected for bank1. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 - * @arg OB_PCROP_SECTOR__All - * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 - * @arg OB_PCROP_SECTOR__All - * @param Banks Disable PCROP protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) - { - assert_param(IS_OB_PCROP(SectorBank1)); - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~SectorBank1); - } - else - { - /*Write protection done on sectors of BANK2*/ - assert_param(IS_OB_PCROP(SectorBank2)); - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); - } - - /*Write protection on all sector of BANK2*/ - if (Banks == FLASH_BANK_BOTH) - { - assert_param(IS_OB_PCROP(SectorBank2)); - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); - } - } - - } - - return status; - -} - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/** - * @brief Mass erase of FLASH memory - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @param Banks Banks to be erased - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * - * @retval None - */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) -{ - /* Check the parameters */ - assert_param(IS_VOLTAGERANGE(VoltageRange)); - assert_param(IS_FLASH_BANK(Banks)); - - /* If the previous operation is completed, proceed to erase all sectors */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_CR_MER; - FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); -} - -/** - * @brief Erase the specified FLASH memory sector - * @param Sector FLASH sector to erase - * The value of this parameter depend on device used within the same series - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @retval None - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) -{ - uint32_t tmp_psize = 0U; - - /* Check the parameters */ - assert_param(IS_FLASH_SECTOR(Sector)); - assert_param(IS_VOLTAGERANGE(VoltageRange)); - - if (VoltageRange == FLASH_VOLTAGE_RANGE_1) - { - tmp_psize = FLASH_PSIZE_BYTE; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) - { - tmp_psize = FLASH_PSIZE_HALF_WORD; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) - { - tmp_psize = FLASH_PSIZE_WORD; - } - else - { - tmp_psize = FLASH_PSIZE_DOUBLE_WORD; - } - - /* If the previous operation is completed, proceed to erase the sector */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= tmp_psize; - CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); - FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); - FLASH->CR |= FLASH_CR_STRT; -} - -/** - * @brief Enable the write protection of the desired bank 1 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * The value of this parameter depend on device used within the same series - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); - } - - return status; -} - -/** - * @brief Disable the write protection of the desired bank 1 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * The value of this parameter depend on device used within the same series - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; - } - - return status; -} -#endif /* STM32F40xxx || STM32F41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Enable the read/write protection (PCROP) of the desired sectors. - * @note This function can be used only for STM32F401xx devices. - * @param Sector specifies the sector(s) to be read/write protected or unprotected. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 - * @arg OB_PCROP_Sector_All - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_PCROP(Sector)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)Sector; - } - - return status; -} - - -/** - * @brief Disable the read/write protection (PCROP) of the desired sectors. - * @note This function can be used only for STM32F401xx devices. - * @param Sector specifies the sector(s) to be read/write protected or unprotected. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 - * @arg OB_PCROP_Sector_All - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_PCROP(Sector)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~Sector); - } - - return status; - -} -#endif /* STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -/** - * @brief Set the read protection level. - * @param Level specifies the read protection level. - * This parameter can be one of the following values: - * @arg OB_RDP_LEVEL_0: No protection - * @arg OB_RDP_LEVEL_1: Read protection of the memory - * @arg OB_RDP_LEVEL_2: Full chip protection - * - * @note WARNING: When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_RDP_LEVEL(Level)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint8_t *)OPTCR_BYTE1_ADDRESS = Level; - } - - return status; -} - -/** - * @brief Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. - * @param Iwdg Selects the IWDG mode - * This parameter can be one of the following values: - * @arg OB_IWDG_SW: Software IWDG selected - * @arg OB_IWDG_HW: Hardware IWDG selected - * @param Stop Reset event when entering STOP mode. - * This parameter can be one of the following values: - * @arg OB_STOP_NO_RST: No reset generated when entering in STOP - * @arg OB_STOP_RST: Reset generated when entering in STOP - * @param Stdby Reset event when entering Standby mode. - * This parameter can be one of the following values: - * @arg OB_STDBY_NO_RST: No reset generated when entering in STANDBY - * @arg OB_STDBY_RST: Reset generated when entering in STANDBY - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby) -{ - uint8_t optiontmp = 0xFF; - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_IWDG_SOURCE(Iwdg)); - assert_param(IS_OB_STOP_SOURCE(Stop)); - assert_param(IS_OB_STDBY_SOURCE(Stdby)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F); - - /* Update User Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = Iwdg | (uint8_t)(Stdby | (uint8_t)(Stop | ((uint8_t)optiontmp))); - } - - return status; -} - -/** - * @brief Set the BOR Level. - * @param Level specifies the Option Bytes BOR Reset Level. - * This parameter can be one of the following values: - * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V - * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V - * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V - * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level) -{ - /* Check the parameters */ - assert_param(IS_OB_BOR_LEVEL(Level)); - - /* Set the BOR Level */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV); - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= Level; - - return HAL_OK; - -} - -/** - * @brief Return the FLASH User Option Byte value. - * @retval uint8_t FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1) - * and RST_STDBY(Bit2). - */ -static uint8_t FLASH_OB_GetUser(void) -{ - /* Return the User Option Byte */ - return ((uint8_t)(FLASH->OPTCR & 0xE0)); -} - -/** - * @brief Return the FLASH Write Protection Option Bytes value. - * @retval uint16_t FLASH Write Protection Option Bytes value - */ -static uint16_t FLASH_OB_GetWRP(void) -{ - /* Return the FLASH write protection Register value */ - return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); -} - -/** - * @brief Returns the FLASH Read Protection level. - * @retval FLASH ReadOut Protection Status: - * This parameter can be one of the following values: - * @arg OB_RDP_LEVEL_0: No protection - * @arg OB_RDP_LEVEL_1: Read protection of the memory - * @arg OB_RDP_LEVEL_2: Full chip protection - */ -static uint8_t FLASH_OB_GetRDP(void) -{ - uint8_t readstatus = OB_RDP_LEVEL_0; - - if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_2) - { - readstatus = OB_RDP_LEVEL_2; - } - else if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_0) - { - readstatus = OB_RDP_LEVEL_0; - } - else - { - readstatus = OB_RDP_LEVEL_1; - } - - return readstatus; -} - -/** - * @brief Returns the FLASH BOR level. - * @retval uint8_t The FLASH BOR level: - * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V - * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V - * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V - * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V - */ -static uint8_t FLASH_OB_GetBOR(void) -{ - /* Return the FLASH BOR level */ - return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C); -} - -/** - * @brief Flush the instruction and data caches - * @retval None - */ -void FLASH_FlushCaches(void) -{ - /* Flush instruction cache */ - if (READ_BIT(FLASH->ACR, FLASH_ACR_ICEN) != RESET) - { - /* Disable instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_DISABLE(); - /* Reset instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_RESET(); - /* Enable instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); - } - - /* Flush data cache */ - if (READ_BIT(FLASH->ACR, FLASH_ACR_DCEN) != RESET) - { - /* Disable data cache */ - __HAL_FLASH_DATA_CACHE_DISABLE(); - /* Reset data cache */ - __HAL_FLASH_DATA_CACHE_RESET(); - /* Enable data cache */ - __HAL_FLASH_DATA_CACHE_ENABLE(); - } -} - -/** - * @} - */ - -#endif /* HAL_FLASH_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ex.c + * @author MCD Application Team + * @brief Extended FLASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the FLASH extension peripheral: + * + Extended programming operations functions + * + @verbatim + ============================================================================== + ##### Flash Extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the FLASH interface for STM32F427xx/437xx and + STM32F429xx/439xx devices contains the following additional features + + (+) Capacity up to 2 Mbyte with dual bank architecture supporting read-while-write + capability (RWW) + (+) Dual bank memory organization + (+) PCROP protection for all banks + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to configure and program the FLASH memory + of all STM32F427xx/437xx, STM32F429xx/439xx, STM32F469xx/479xx and STM32F446xx + devices. It includes + (#) FLASH Memory Erase functions: + (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and + HAL_FLASH_Lock() functions + (++) Erase function: Erase sector, erase all sectors + (++) There are two modes of erase : + (+++) Polling Mode using HAL_FLASHEx_Erase() + (+++) Interrupt Mode using HAL_FLASHEx_Erase_IT() + + (#) Option Bytes Programming functions: Use HAL_FLASHEx_OBProgram() to : + (++) Set/Reset the write protection + (++) Set the Read protection Level + (++) Set the BOR level + (++) Program the user Option Bytes + (#) Advanced Option Bytes Programming functions: Use HAL_FLASHEx_AdvOBProgram() to : + (++) Extended space (bank 2) erase function + (++) Full FLASH space (2 Mo) erase (bank 1 and bank 2) + (++) Dual Boot activation + (++) Write protection configuration for bank 2 + (++) PCROP protection configuration and control for both banks + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASHEx FLASHEx + * @brief FLASH HAL Extension module driver + * @{ + */ + +#ifdef HAL_FLASH_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Constants + * @{ + */ +#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Variables + * @{ + */ +extern FLASH_ProcessTypeDef pFlash; +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Functions + * @{ + */ +/* Option bytes control */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level); +static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby); +static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level); +static uint8_t FLASH_OB_GetUser(void); +static uint16_t FLASH_OB_GetWRP(void); +static uint8_t FLASH_OB_GetRDP(void); +static uint8_t FLASH_OB_GetBOR(void); + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ + defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector); +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +extern HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASHEx_Exported_Functions FLASHEx Exported Functions + * @{ + */ + +/** @defgroup FLASHEx_Exported_Functions_Group1 Extended IO operation functions + * @brief Extended IO operation functions + * +@verbatim + =============================================================================== + ##### Extended programming operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the Extension FLASH + programming operations. + +@endverbatim + * @{ + */ +/** + * @brief Perform a mass erase or erase the specified FLASH memory sectors + * @param[in] pEraseInit pointer to an FLASH_EraseInitTypeDef structure that + * contains the configuration information for the erasing. + * + * @param[out] SectorError pointer to variable that + * contains the configuration information on faulty sector in case of error + * (0xFFFFFFFFU means that all the sectors have been correctly erased) + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *SectorError) +{ + HAL_StatusTypeDef status = HAL_ERROR; + uint32_t index = 0U; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Initialization of SectorError variable*/ + *SectorError = 0xFFFFFFFFU; + + if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) + { + /*Mass erase to be done*/ + FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* if the erase operation is completed, disable the MER Bit */ + FLASH->CR &= (~FLASH_MER_BIT); + } + else + { + /* Check the parameters */ + assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); + + /* Erase by sector by sector to be done*/ + for (index = pEraseInit->Sector; index < (pEraseInit->NbSectors + pEraseInit->Sector); index++) + { + FLASH_Erase_Sector(index, (uint8_t) pEraseInit->VoltageRange); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* If the erase operation is completed, disable the SER and SNB Bits */ + CLEAR_BIT(FLASH->CR, (FLASH_CR_SER | FLASH_CR_SNB)); + + if (status != HAL_OK) + { + /* In case of error, stop erase procedure and return the faulty sector*/ + *SectorError = index; + break; + } + } + } + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches(); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Perform a mass erase or erase the specified FLASH memory sectors with interrupt enabled + * @param pEraseInit pointer to an FLASH_EraseInitTypeDef structure that + * contains the configuration information for the erasing. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); + + /* Enable End of FLASH Operation interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); + + /* Enable Error source interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); + + /* Clear pending flags (if any) */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \ + FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); + + if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) + { + /*Mass erase to be done*/ + pFlash.ProcedureOnGoing = FLASH_PROC_MASSERASE; + pFlash.Bank = pEraseInit->Banks; + FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); + } + else + { + /* Erase by sector to be done*/ + + /* Check the parameters */ + assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); + + pFlash.ProcedureOnGoing = FLASH_PROC_SECTERASE; + pFlash.NbSectorsToErase = pEraseInit->NbSectors; + pFlash.Sector = pEraseInit->Sector; + pFlash.VoltageForErase = (uint8_t)pEraseInit->VoltageRange; + + /*Erase 1st sector and wait for IT*/ + FLASH_Erase_Sector(pEraseInit->Sector, pEraseInit->VoltageRange); + } + + return status; +} + +/** + * @brief Program option bytes + * @param pOBInit pointer to an FLASH_OBInitStruct structure that + * contains the configuration information for the programming. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_OPTIONBYTE(pOBInit->OptionType)); + + /*Write protection configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_WRP) == OPTIONBYTE_WRP) + { + assert_param(IS_WRPSTATE(pOBInit->WRPState)); + if (pOBInit->WRPState == OB_WRPSTATE_ENABLE) + { + /*Enable of Write protection on the selected Sector*/ + status = FLASH_OB_EnableWRP(pOBInit->WRPSector, pOBInit->Banks); + } + else + { + /*Disable of Write protection on the selected Sector*/ + status = FLASH_OB_DisableWRP(pOBInit->WRPSector, pOBInit->Banks); + } + } + + /*Read protection configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_RDP) == OPTIONBYTE_RDP) + { + status = FLASH_OB_RDP_LevelConfig(pOBInit->RDPLevel); + } + + /*USER configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_USER) == OPTIONBYTE_USER) + { + status = FLASH_OB_UserConfig(pOBInit->USERConfig & OB_IWDG_SW, + pOBInit->USERConfig & OB_STOP_NO_RST, + pOBInit->USERConfig & OB_STDBY_NO_RST); + } + + /*BOR Level configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_BOR) == OPTIONBYTE_BOR) + { + status = FLASH_OB_BOR_LevelConfig(pOBInit->BORLevel); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Get the Option byte configuration + * @param pOBInit pointer to an FLASH_OBInitStruct structure that + * contains the configuration information for the programming. + * + * @retval None + */ +void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit) +{ + pOBInit->OptionType = OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER | OPTIONBYTE_BOR; + + /*Get WRP*/ + pOBInit->WRPSector = (uint32_t)FLASH_OB_GetWRP(); + + /*Get RDP Level*/ + pOBInit->RDPLevel = (uint32_t)FLASH_OB_GetRDP(); + + /*Get USER*/ + pOBInit->USERConfig = (uint8_t)FLASH_OB_GetUser(); + + /*Get BOR Level*/ + pOBInit->BORLevel = (uint32_t)FLASH_OB_GetBOR(); +} + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Program option bytes + * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that + * contains the configuration information for the programming. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_AdvOBProgram(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Check the parameters */ + assert_param(IS_OBEX(pAdvOBInit->OptionType)); + + /*Program PCROP option byte*/ + if (((pAdvOBInit->OptionType) & OPTIONBYTE_PCROP) == OPTIONBYTE_PCROP) + { + /* Check the parameters */ + assert_param(IS_PCROPSTATE(pAdvOBInit->PCROPState)); + if ((pAdvOBInit->PCROPState) == OB_PCROP_STATE_ENABLE) + { + /*Enable of Write protection on the selected Sector*/ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + status = FLASH_OB_EnablePCROP(pAdvOBInit->Sectors); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + status = FLASH_OB_EnablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + } + else + { + /*Disable of Write protection on the selected Sector*/ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + status = FLASH_OB_DisablePCROP(pAdvOBInit->Sectors); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + status = FLASH_OB_DisablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + } + } + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + /*Program BOOT config option byte*/ + if (((pAdvOBInit->OptionType) & OPTIONBYTE_BOOTCONFIG) == OPTIONBYTE_BOOTCONFIG) + { + status = FLASH_OB_BootConfig(pAdvOBInit->BootConfig); + } +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + + return status; +} + +/** + * @brief Get the OBEX byte configuration + * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that + * contains the configuration information for the programming. + * + * @retval None + */ +void HAL_FLASHEx_AdvOBGetConfig(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) +{ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /*Get Sector*/ + pAdvOBInit->Sectors = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + /*Get Sector for Bank1*/ + pAdvOBInit->SectorsBank1 = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); + + /*Get Sector for Bank2*/ + pAdvOBInit->SectorsBank2 = (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); + + /*Get Boot config OB*/ + pAdvOBInit->BootConfig = *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS; +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ +} + +/** + * @brief Select the Protection Mode + * + * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted + * Global Read Out Protection modification (from level1 to level0) + * @note Once SPRMOD bit is active unprotection of a protected sector is not possible + * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ + * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OB_SelectPCROP(void) +{ + uint8_t optiontmp = 0xFF; + + /* Mask SPRMOD bit */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); + + /* Update Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_SELECTED | optiontmp); + + return HAL_OK; +} + +/** + * @brief Deselect the Protection Mode + * + * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted + * Global Read Out Protection modification (from level1 to level0) + * @note Once SPRMOD bit is active unprotection of a protected sector is not possible + * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ + * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OB_DeSelectPCROP(void) +{ + uint8_t optiontmp = 0xFF; + + /* Mask SPRMOD bit */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); + + /* Update Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_DESELECTED | optiontmp); + + return HAL_OK; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx ||\ + STM32F411xE || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Returns the FLASH Write Protection Option Bytes value for Bank 2 + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx devices. + * @retval The FLASH Write Protection Option Bytes value + */ +uint16_t HAL_FLASHEx_OB_GetBank2WRP(void) +{ + /* Return the FLASH write protection Register value */ + return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +/** + * @} + */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Full erase of FLASH memory sectors + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @param Banks Banks to be erased + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * @arg FLASH_BANK_2: Bank2 to be erased + * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased + * + * @retval HAL Status + */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) +{ + /* Check the parameters */ + assert_param(IS_VOLTAGERANGE(VoltageRange)); + assert_param(IS_FLASH_BANK(Banks)); + + /* if the previous operation is completed, proceed to erase all sectors */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + + if (Banks == FLASH_BANK_BOTH) + { + /* bank1 & bank2 will be erased*/ + FLASH->CR |= FLASH_MER_BIT; + } + else if (Banks == FLASH_BANK_1) + { + /*Only bank1 will be erased*/ + FLASH->CR |= FLASH_CR_MER1; + } + else + { + /*Only bank2 will be erased*/ + FLASH->CR |= FLASH_CR_MER2; + } + FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); +} + +/** + * @brief Erase the specified FLASH memory sector + * @param Sector FLASH sector to erase + * The value of this parameter depend on device used within the same series + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval None + */ +void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0U; + + /* Check the parameters */ + assert_param(IS_FLASH_SECTOR(Sector)); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if (VoltageRange == FLASH_VOLTAGE_RANGE_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + + /* Need to add offset of 4 when sector higher than FLASH_SECTOR_11 */ + if (Sector > FLASH_SECTOR_11) + { + Sector += 4U; + } + /* If the previous operation is completed, proceed to erase the sector */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= tmp_psize; + CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); + FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); + FLASH->CR |= FLASH_CR_STRT; +} + +/** + * @brief Enable the write protection of the desired bank1 or bank 2 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * This parameter can be one of the following values: + * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 + * @arg OB_WRP_SECTOR_All + * @note BANK2 starts from OB_WRP_SECTOR_12 + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL FLASH State + */ +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || + (WRPSector < OB_WRP_SECTOR_12)) + { + if (WRPSector == OB_WRP_SECTOR_All) + { + /*Write protection on all sector of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + else + { + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); + } + } + else + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + + /*Write protection on all sector of BANK2*/ + if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + } + + } + return status; +} + +/** + * @brief Disable the write protection of the desired bank1 or bank 2 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * This parameter can be one of the following values: + * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 + * @arg OB_WRP_Sector_All + * @note BANK2 starts from OB_WRP_SECTOR_12 + * + * @param Banks Disable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * @arg FLASH_BANK_2: Bank2 to be erased + * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || + (WRPSector < OB_WRP_SECTOR_12)) + { + if (WRPSector == OB_WRP_SECTOR_All) + { + /*Write protection on all sector of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + else + { + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; + } + } + else + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + + /*Write protection on all sector of BANK2*/ + if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + } + + } + + return status; +} + +/** + * @brief Configure the Dual Bank Boot. + * + * @note This function can be used only for STM32F42xxx/43xxx devices. + * + * @param BootConfig specifies the Dual Bank Boot Option byte. + * This parameter can be one of the following values: + * @arg OB_Dual_BootEnabled: Dual Bank Boot Enable + * @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled + * @retval None + */ +static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_BOOT(BootConfig)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /* Set Dual Bank Boot */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2); + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= BootConfig; + } + + return status; +} + +/** + * @brief Enable the read/write protection (PCROP) of the desired + * sectors of Bank 1 and/or Bank 2. + * @note This function can be used only for STM32F42xxx/43xxx devices. + * @param SectorBank1 Specifies the sector(s) to be read/write protected or unprotected for bank1. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 + * @arg OB_PCROP_SECTOR__All + * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 + * @arg OB_PCROP_SECTOR__All + * @param Banks Enable PCROP protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) + { + assert_param(IS_OB_PCROP(SectorBank1)); + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)SectorBank1; + } + else + { + assert_param(IS_OB_PCROP(SectorBank2)); + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; + } + + /*Write protection on all sector of BANK2*/ + if (Banks == FLASH_BANK_BOTH) + { + assert_param(IS_OB_PCROP(SectorBank2)); + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; + } + } + + } + + return status; +} + + +/** + * @brief Disable the read/write protection (PCROP) of the desired + * sectors of Bank 1 and/or Bank 2. + * @note This function can be used only for STM32F42xxx/43xxx devices. + * @param SectorBank1 specifies the sector(s) to be read/write protected or unprotected for bank1. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 + * @arg OB_PCROP_SECTOR__All + * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 + * @arg OB_PCROP_SECTOR__All + * @param Banks Disable PCROP protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) + { + assert_param(IS_OB_PCROP(SectorBank1)); + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~SectorBank1); + } + else + { + /*Write protection done on sectors of BANK2*/ + assert_param(IS_OB_PCROP(SectorBank2)); + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); + } + + /*Write protection on all sector of BANK2*/ + if (Banks == FLASH_BANK_BOTH) + { + assert_param(IS_OB_PCROP(SectorBank2)); + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); + } + } + + } + + return status; + +} + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +/** + * @brief Mass erase of FLASH memory + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @param Banks Banks to be erased + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * + * @retval None + */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) +{ + /* Check the parameters */ + assert_param(IS_VOLTAGERANGE(VoltageRange)); + assert_param(IS_FLASH_BANK(Banks)); + + /* If the previous operation is completed, proceed to erase all sectors */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_CR_MER; + FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); +} + +/** + * @brief Erase the specified FLASH memory sector + * @param Sector FLASH sector to erase + * The value of this parameter depend on device used within the same series + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval None + */ +void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0U; + + /* Check the parameters */ + assert_param(IS_FLASH_SECTOR(Sector)); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if (VoltageRange == FLASH_VOLTAGE_RANGE_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + + /* If the previous operation is completed, proceed to erase the sector */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= tmp_psize; + CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); + FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); + FLASH->CR |= FLASH_CR_STRT; +} + +/** + * @brief Enable the write protection of the desired bank 1 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * The value of this parameter depend on device used within the same series + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); + } + + return status; +} + +/** + * @brief Disable the write protection of the desired bank 1 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * The value of this parameter depend on device used within the same series + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; + } + + return status; +} +#endif /* STM32F40xxx || STM32F41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Enable the read/write protection (PCROP) of the desired sectors. + * @note This function can be used only for STM32F401xx devices. + * @param Sector specifies the sector(s) to be read/write protected or unprotected. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 + * @arg OB_PCROP_Sector_All + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_PCROP(Sector)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)Sector; + } + + return status; +} + + +/** + * @brief Disable the read/write protection (PCROP) of the desired sectors. + * @note This function can be used only for STM32F401xx devices. + * @param Sector specifies the sector(s) to be read/write protected or unprotected. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 + * @arg OB_PCROP_Sector_All + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_PCROP(Sector)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~Sector); + } + + return status; + +} +#endif /* STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +/** + * @brief Set the read protection level. + * @param Level specifies the read protection level. + * This parameter can be one of the following values: + * @arg OB_RDP_LEVEL_0: No protection + * @arg OB_RDP_LEVEL_1: Read protection of the memory + * @arg OB_RDP_LEVEL_2: Full chip protection + * + * @note WARNING: When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_RDP_LEVEL(Level)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint8_t *)OPTCR_BYTE1_ADDRESS = Level; + } + + return status; +} + +/** + * @brief Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @param Iwdg Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param Stop Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NO_RST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param Stdby Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NO_RST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby) +{ + uint8_t optiontmp = 0xFF; + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(Iwdg)); + assert_param(IS_OB_STOP_SOURCE(Stop)); + assert_param(IS_OB_STDBY_SOURCE(Stdby)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F); + + /* Update User Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = Iwdg | (uint8_t)(Stdby | (uint8_t)(Stop | ((uint8_t)optiontmp))); + } + + return status; +} + +/** + * @brief Set the BOR Level. + * @param Level specifies the Option Bytes BOR Reset Level. + * This parameter can be one of the following values: + * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level) +{ + /* Check the parameters */ + assert_param(IS_OB_BOR_LEVEL(Level)); + + /* Set the BOR Level */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV); + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= Level; + + return HAL_OK; + +} + +/** + * @brief Return the FLASH User Option Byte value. + * @retval uint8_t FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +static uint8_t FLASH_OB_GetUser(void) +{ + /* Return the User Option Byte */ + return ((uint8_t)(FLASH->OPTCR & 0xE0)); +} + +/** + * @brief Return the FLASH Write Protection Option Bytes value. + * @retval uint16_t FLASH Write Protection Option Bytes value + */ +static uint16_t FLASH_OB_GetWRP(void) +{ + /* Return the FLASH write protection Register value */ + return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); +} + +/** + * @brief Returns the FLASH Read Protection level. + * @retval FLASH ReadOut Protection Status: + * This parameter can be one of the following values: + * @arg OB_RDP_LEVEL_0: No protection + * @arg OB_RDP_LEVEL_1: Read protection of the memory + * @arg OB_RDP_LEVEL_2: Full chip protection + */ +static uint8_t FLASH_OB_GetRDP(void) +{ + uint8_t readstatus = OB_RDP_LEVEL_0; + + if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_2) + { + readstatus = OB_RDP_LEVEL_2; + } + else if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_0) + { + readstatus = OB_RDP_LEVEL_0; + } + else + { + readstatus = OB_RDP_LEVEL_1; + } + + return readstatus; +} + +/** + * @brief Returns the FLASH BOR level. + * @retval uint8_t The FLASH BOR level: + * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V + */ +static uint8_t FLASH_OB_GetBOR(void) +{ + /* Return the FLASH BOR level */ + return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C); +} + +/** + * @brief Flush the instruction and data caches + * @retval None + */ +void FLASH_FlushCaches(void) +{ + /* Flush instruction cache */ + if (READ_BIT(FLASH->ACR, FLASH_ACR_ICEN) != RESET) + { + /* Disable instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_DISABLE(); + /* Reset instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_RESET(); + /* Enable instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); + } + + /* Flush data cache */ + if (READ_BIT(FLASH->ACR, FLASH_ACR_DCEN) != RESET) + { + /* Disable data cache */ + __HAL_FLASH_DATA_CACHE_DISABLE(); + /* Reset data cache */ + __HAL_FLASH_DATA_CACHE_RESET(); + /* Enable data cache */ + __HAL_FLASH_DATA_CACHE_ENABLE(); + } +} + +/** + * @} + */ + +#endif /* HAL_FLASH_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c index 952595b..fdc5a4c 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c @@ -1,172 +1,172 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ramfunc.c - * @author MCD Application Team - * @brief FLASH RAMFUNC module driver. - * This file provides a FLASH firmware functions which should be - * executed from internal SRAM - * + Stop/Start the flash interface while System Run - * + Enable/Disable the flash sleep while System Run - @verbatim - ============================================================================== - ##### APIs executed from Internal RAM ##### - ============================================================================== - [..] - *** ARM Compiler *** - -------------------- - [..] RAM functions are defined using the toolchain options. - Functions that are be executed in RAM should reside in a separate - source module. Using the 'Options for File' dialog you can simply change - the 'Code / Const' area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the - Options for Target' dialog. - - *** ICCARM Compiler *** - ----------------------- - [..] RAM functions are defined using a specific toolchain keyword "__ramfunc". - - *** GNU Compiler *** - -------------------- - [..] RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASH_RAMFUNC FLASH RAMFUNC - * @brief FLASH functions executed from RAM - * @{ - */ -#ifdef HAL_FLASH_MODULE_ENABLED -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASH_RAMFUNC_Exported_Functions FLASH RAMFUNC Exported Functions - * @{ - */ - -/** @defgroup FLASH_RAMFUNC_Exported_Functions_Group1 Peripheral features functions executed from internal RAM - * @brief Peripheral Extended features functions - * -@verbatim - - =============================================================================== - ##### ramfunc functions ##### - =============================================================================== - [..] - This subsection provides a set of functions that should be executed from RAM - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Stop the flash interface while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Stop the flash interface while System Run */ - SET_BIT(PWR->CR, PWR_CR_FISSR); - - return HAL_OK; -} - -/** - * @brief Start the flash interface while System Run - * @note This mode is only available for STM32F411xx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Start the flash interface while System Run */ - CLEAR_BIT(PWR->CR, PWR_CR_FISSR); - - return HAL_OK; -} - -/** - * @brief Enable the flash sleep while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode could n't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Enable the flash sleep while System Run */ - SET_BIT(PWR->CR, PWR_CR_FMSSR); - - return HAL_OK; -} - -/** - * @brief Disable the flash sleep while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Disable the flash sleep while System Run */ - CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -#endif /* HAL_FLASH_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ramfunc.c + * @author MCD Application Team + * @brief FLASH RAMFUNC module driver. + * This file provides a FLASH firmware functions which should be + * executed from internal SRAM + * + Stop/Start the flash interface while System Run + * + Enable/Disable the flash sleep while System Run + @verbatim + ============================================================================== + ##### APIs executed from Internal RAM ##### + ============================================================================== + [..] + *** ARM Compiler *** + -------------------- + [..] RAM functions are defined using the toolchain options. + Functions that are be executed in RAM should reside in a separate + source module. Using the 'Options for File' dialog you can simply change + the 'Code / Const' area of a module to a memory space in physical RAM. + Available memory areas are declared in the 'Target' tab of the + Options for Target' dialog. + + *** ICCARM Compiler *** + ----------------------- + [..] RAM functions are defined using a specific toolchain keyword "__ramfunc". + + *** GNU Compiler *** + -------------------- + [..] RAM functions are defined using a specific toolchain attribute + "__attribute__((section(".RamFunc")))". + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASH_RAMFUNC FLASH RAMFUNC + * @brief FLASH functions executed from RAM + * @{ + */ +#ifdef HAL_FLASH_MODULE_ENABLED +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASH_RAMFUNC_Exported_Functions FLASH RAMFUNC Exported Functions + * @{ + */ + +/** @defgroup FLASH_RAMFUNC_Exported_Functions_Group1 Peripheral features functions executed from internal RAM + * @brief Peripheral Extended features functions + * +@verbatim + + =============================================================================== + ##### ramfunc functions ##### + =============================================================================== + [..] + This subsection provides a set of functions that should be executed from RAM + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Stop the flash interface while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Stop the flash interface while System Run */ + SET_BIT(PWR->CR, PWR_CR_FISSR); + + return HAL_OK; +} + +/** + * @brief Start the flash interface while System Run + * @note This mode is only available for STM32F411xx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Start the flash interface while System Run */ + CLEAR_BIT(PWR->CR, PWR_CR_FISSR); + + return HAL_OK; +} + +/** + * @brief Enable the flash sleep while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode could n't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Enable the flash sleep while System Run */ + SET_BIT(PWR->CR, PWR_CR_FMSSR); + + return HAL_OK; +} + +/** + * @brief Disable the flash sleep while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Disable the flash sleep while System Run */ + CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +#endif /* HAL_FLASH_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c index b3ce9bb..184fe58 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c @@ -1,533 +1,533 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio.c - * @author MCD Application Team - * @brief GPIO HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the General Purpose Input/Output (GPIO) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### GPIO Peripheral features ##### - ============================================================================== - [..] - Subject to the specific hardware characteristics of each I/O port listed in the datasheet, each - port bit of the General Purpose IO (GPIO) Ports, can be individually configured by software - in several modes: - (+) Input mode - (+) Analog mode - (+) Output mode - (+) Alternate function mode - (+) External interrupt/event lines - - [..] - During and just after reset, the alternate functions and external interrupt - lines are not active and the I/O ports are configured in input floating mode. - - [..] - All GPIO pins have weak internal pull-up and pull-down resistors, which can be - activated or not. - - [..] - In Output or Alternate mode, each IO can be configured on open-drain or push-pull - type and the IO speed can be selected depending on the VDD value. - - [..] - All ports have external interrupt/event capability. To use external interrupt - lines, the port must be configured in input mode. All available GPIO pins are - connected to the 16 external interrupt/event lines from EXTI0 to EXTI15. - - [..] - The external interrupt/event controller consists of up to 23 edge detectors - (16 lines are connected to GPIO) for generating event/interrupt requests (each - input line can be independently configured to select the type (interrupt or event) - and the corresponding trigger event (rising or falling or both). Each line can - also be masked independently. - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Enable the GPIO AHB clock using the following function: __HAL_RCC_GPIOx_CLK_ENABLE(). - - (#) Configure the GPIO pin(s) using HAL_GPIO_Init(). - (++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure - (++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef - structure. - (++) In case of Output or alternate function mode selection: the speed is - configured through "Speed" member from GPIO_InitTypeDef structure. - (++) In alternate mode is selection, the alternate function connected to the IO - is configured through "Alternate" member from GPIO_InitTypeDef structure. - (++) Analog mode is required when a pin is to be used as ADC channel - or DAC output. - (++) In case of external interrupt/event selection the "Mode" member from - GPIO_InitTypeDef structure select the type (interrupt or event) and - the corresponding trigger event (rising or falling or both). - - (#) In case of external interrupt/event mode selection, configure NVIC IRQ priority - mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using - HAL_NVIC_EnableIRQ(). - - (#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin(). - - (#) To set/reset the level of a pin configured in output mode use - HAL_GPIO_WritePin()/HAL_GPIO_TogglePin(). - - (#) To lock pin configuration until next reset use HAL_GPIO_LockPin(). - - - (#) During and just after reset, the alternate functions are not - active and the GPIO pins are configured in input floating mode (except JTAG - pins). - - (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose - (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has - priority over the GPIO function. - - (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as - general purpose PH0 and PH1, respectively, when the HSE oscillator is off. - The HSE has priority over the GPIO function. - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIO GPIO - * @brief GPIO HAL module driver - * @{ - */ - -#ifdef HAL_GPIO_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup GPIO_Private_Constants GPIO Private Constants - * @{ - */ - -#define GPIO_NUMBER 16U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Functions GPIO Exported Functions - * @{ - */ - -/** @defgroup GPIO_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to initialize and de-initialize the GPIOs - to be ready for use. - -@endverbatim - * @{ - */ - - -/** - * @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_Init. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains - * the configuration information for the specified GPIO peripheral. - * @retval None - */ -void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init) -{ - uint32_t position; - uint32_t ioposition = 0x00U; - uint32_t iocurrent = 0x00U; - uint32_t temp = 0x00U; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - assert_param(IS_GPIO_PIN(GPIO_Init->Pin)); - assert_param(IS_GPIO_MODE(GPIO_Init->Mode)); - - /* Configure the port pins */ - for(position = 0U; position < GPIO_NUMBER; position++) - { - /* Get the IO position */ - ioposition = 0x01U << position; - /* Get the current IO position */ - iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; - - if(iocurrent == ioposition) - { - /*--------------------- GPIO Mode Configuration ------------------------*/ - /* In case of Output or Alternate function mode selection */ - if(((GPIO_Init->Mode & GPIO_MODE) == MODE_OUTPUT) || \ - (GPIO_Init->Mode & GPIO_MODE) == MODE_AF) - { - /* Check the Speed parameter */ - assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); - /* Configure the IO Speed */ - temp = GPIOx->OSPEEDR; - temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); - temp |= (GPIO_Init->Speed << (position * 2U)); - GPIOx->OSPEEDR = temp; - - /* Configure the IO Output Type */ - temp = GPIOx->OTYPER; - temp &= ~(GPIO_OTYPER_OT_0 << position) ; - temp |= (((GPIO_Init->Mode & OUTPUT_TYPE) >> OUTPUT_TYPE_Pos) << position); - GPIOx->OTYPER = temp; - } - - if((GPIO_Init->Mode & GPIO_MODE) != MODE_ANALOG) - { - /* Check the parameters */ - assert_param(IS_GPIO_PULL(GPIO_Init->Pull)); - - /* Activate the Pull-up or Pull down resistor for the current IO */ - temp = GPIOx->PUPDR; - temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); - temp |= ((GPIO_Init->Pull) << (position * 2U)); - GPIOx->PUPDR = temp; - } - - /* In case of Alternate function mode selection */ - if((GPIO_Init->Mode & GPIO_MODE) == MODE_AF) - { - /* Check the Alternate function parameter */ - assert_param(IS_GPIO_AF(GPIO_Init->Alternate)); - /* Configure Alternate function mapped with the current IO */ - temp = GPIOx->AFR[position >> 3U]; - temp &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; - temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & 0x07U) * 4U)); - GPIOx->AFR[position >> 3U] = temp; - } - - /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ - temp = GPIOx->MODER; - temp &= ~(GPIO_MODER_MODER0 << (position * 2U)); - temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2U)); - GPIOx->MODER = temp; - - /*--------------------- EXTI Mode Configuration ------------------------*/ - /* Configure the External Interrupt or event for the current IO */ - if((GPIO_Init->Mode & EXTI_MODE) != 0x00U) - { - /* Enable SYSCFG Clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - temp = SYSCFG->EXTICR[position >> 2U]; - temp &= ~(0x0FU << (4U * (position & 0x03U))); - temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U))); - SYSCFG->EXTICR[position >> 2U] = temp; - - /* Clear Rising Falling edge configuration */ - temp = EXTI->RTSR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & TRIGGER_RISING) != 0x00U) - { - temp |= iocurrent; - } - EXTI->RTSR = temp; - - temp = EXTI->FTSR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & TRIGGER_FALLING) != 0x00U) - { - temp |= iocurrent; - } - EXTI->FTSR = temp; - - temp = EXTI->EMR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & EXTI_EVT) != 0x00U) - { - temp |= iocurrent; - } - EXTI->EMR = temp; - - /* Clear EXTI line configuration */ - temp = EXTI->IMR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & EXTI_IT) != 0x00U) - { - temp |= iocurrent; - } - EXTI->IMR = temp; - } - } - } -} - -/** - * @brief De-initializes the GPIOx peripheral registers to their default reset values. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to be written. - * This parameter can be one of GPIO_PIN_x where x can be (0..15). - * @retval None - */ -void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin) -{ - uint32_t position; - uint32_t ioposition = 0x00U; - uint32_t iocurrent = 0x00U; - uint32_t tmp = 0x00U; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - - /* Configure the port pins */ - for(position = 0U; position < GPIO_NUMBER; position++) - { - /* Get the IO position */ - ioposition = 0x01U << position; - /* Get the current IO position */ - iocurrent = (GPIO_Pin) & ioposition; - - if(iocurrent == ioposition) - { - /*------------------------- EXTI Mode Configuration --------------------*/ - tmp = SYSCFG->EXTICR[position >> 2U]; - tmp &= (0x0FU << (4U * (position & 0x03U))); - if(tmp == ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U)))) - { - /* Clear EXTI line configuration */ - EXTI->IMR &= ~((uint32_t)iocurrent); - EXTI->EMR &= ~((uint32_t)iocurrent); - - /* Clear Rising Falling edge configuration */ - EXTI->FTSR &= ~((uint32_t)iocurrent); - EXTI->RTSR &= ~((uint32_t)iocurrent); - - /* Configure the External Interrupt or event for the current IO */ - tmp = 0x0FU << (4U * (position & 0x03U)); - SYSCFG->EXTICR[position >> 2U] &= ~tmp; - } - - /*------------------------- GPIO Mode Configuration --------------------*/ - /* Configure IO Direction in Input Floating Mode */ - GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (position * 2U)); - - /* Configure the default Alternate Function in current IO */ - GPIOx->AFR[position >> 3U] &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; - - /* Deactivate the Pull-up and Pull-down resistor for the current IO */ - GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); - - /* Configure the default value IO Output Type */ - GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ; - - /* Configure the default value for IO Speed */ - GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); - } - } -} - -/** - * @} - */ - -/** @defgroup GPIO_Exported_Functions_Group2 IO operation functions - * @brief GPIO Read and Write - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Reads the specified input port pin. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to read. - * This parameter can be GPIO_PIN_x where x can be (0..15). - * @retval The input port pin value. - */ -GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - GPIO_PinState bitstatus; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET) - { - bitstatus = GPIO_PIN_SET; - } - else - { - bitstatus = GPIO_PIN_RESET; - } - return bitstatus; -} - -/** - * @brief Sets or clears the selected data port bit. - * - * @note This function uses GPIOx_BSRR register to allow atomic read/modify - * accesses. In this way, there is no risk of an IRQ occurring between - * the read and the modify access. - * - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to be written. - * This parameter can be one of GPIO_PIN_x where x can be (0..15). - * @param PinState specifies the value to be written to the selected bit. - * This parameter can be one of the GPIO_PinState enum values: - * @arg GPIO_PIN_RESET: to clear the port pin - * @arg GPIO_PIN_SET: to set the port pin - * @retval None - */ -void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState) -{ - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - assert_param(IS_GPIO_PIN_ACTION(PinState)); - - if(PinState != GPIO_PIN_RESET) - { - GPIOx->BSRR = GPIO_Pin; - } - else - { - GPIOx->BSRR = (uint32_t)GPIO_Pin << 16U; - } -} - -/** - * @brief Toggles the specified GPIO pins. - * @param GPIOx Where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin Specifies the pins to be toggled. - * @retval None - */ -void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - uint32_t odr; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - /* get current Output Data Register value */ - odr = GPIOx->ODR; - - /* Set selected pins that were at low level, and reset ones that were high */ - GPIOx->BSRR = ((odr & GPIO_Pin) << GPIO_NUMBER) | (~odr & GPIO_Pin); -} - -/** - * @brief Locks GPIO Pins configuration registers. - * @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, - * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. - * @note The configuration of the locked GPIO pins can no longer be modified - * until the next reset. - * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F4 family - * @param GPIO_Pin specifies the port bit to be locked. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15). - * @retval None - */ -HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - __IO uint32_t tmp = GPIO_LCKR_LCKK; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - /* Apply lock key write sequence */ - tmp |= GPIO_Pin; - /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ - GPIOx->LCKR = tmp; - /* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */ - GPIOx->LCKR = GPIO_Pin; - /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ - GPIOx->LCKR = tmp; - /* Read LCKR register. This read is mandatory to complete key lock sequence */ - tmp = GPIOx->LCKR; - - /* Read again in order to confirm lock is active */ - if((GPIOx->LCKR & GPIO_LCKR_LCKK) != RESET) - { - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief This function handles EXTI interrupt request. - * @param GPIO_Pin Specifies the pins connected EXTI line - * @retval None - */ -void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) -{ - /* EXTI line interrupt detected */ - if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) - { - __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); - HAL_GPIO_EXTI_Callback(GPIO_Pin); - } -} - -/** - * @brief EXTI line detection callbacks. - * @param GPIO_Pin Specifies the pins connected EXTI line - * @retval None - */ -__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(GPIO_Pin); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_GPIO_EXTI_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - - -/** - * @} - */ - -#endif /* HAL_GPIO_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_gpio.c + * @author MCD Application Team + * @brief GPIO HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the General Purpose Input/Output (GPIO) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### GPIO Peripheral features ##### + ============================================================================== + [..] + Subject to the specific hardware characteristics of each I/O port listed in the datasheet, each + port bit of the General Purpose IO (GPIO) Ports, can be individually configured by software + in several modes: + (+) Input mode + (+) Analog mode + (+) Output mode + (+) Alternate function mode + (+) External interrupt/event lines + + [..] + During and just after reset, the alternate functions and external interrupt + lines are not active and the I/O ports are configured in input floating mode. + + [..] + All GPIO pins have weak internal pull-up and pull-down resistors, which can be + activated or not. + + [..] + In Output or Alternate mode, each IO can be configured on open-drain or push-pull + type and the IO speed can be selected depending on the VDD value. + + [..] + All ports have external interrupt/event capability. To use external interrupt + lines, the port must be configured in input mode. All available GPIO pins are + connected to the 16 external interrupt/event lines from EXTI0 to EXTI15. + + [..] + The external interrupt/event controller consists of up to 23 edge detectors + (16 lines are connected to GPIO) for generating event/interrupt requests (each + input line can be independently configured to select the type (interrupt or event) + and the corresponding trigger event (rising or falling or both). Each line can + also be masked independently. + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable the GPIO AHB clock using the following function: __HAL_RCC_GPIOx_CLK_ENABLE(). + + (#) Configure the GPIO pin(s) using HAL_GPIO_Init(). + (++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure + (++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef + structure. + (++) In case of Output or alternate function mode selection: the speed is + configured through "Speed" member from GPIO_InitTypeDef structure. + (++) In alternate mode is selection, the alternate function connected to the IO + is configured through "Alternate" member from GPIO_InitTypeDef structure. + (++) Analog mode is required when a pin is to be used as ADC channel + or DAC output. + (++) In case of external interrupt/event selection the "Mode" member from + GPIO_InitTypeDef structure select the type (interrupt or event) and + the corresponding trigger event (rising or falling or both). + + (#) In case of external interrupt/event mode selection, configure NVIC IRQ priority + mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using + HAL_NVIC_EnableIRQ(). + + (#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin(). + + (#) To set/reset the level of a pin configured in output mode use + HAL_GPIO_WritePin()/HAL_GPIO_TogglePin(). + + (#) To lock pin configuration until next reset use HAL_GPIO_LockPin(). + + + (#) During and just after reset, the alternate functions are not + active and the GPIO pins are configured in input floating mode (except JTAG + pins). + + (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose + (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has + priority over the GPIO function. + + (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as + general purpose PH0 and PH1, respectively, when the HSE oscillator is off. + The HSE has priority over the GPIO function. + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup GPIO GPIO + * @brief GPIO HAL module driver + * @{ + */ + +#ifdef HAL_GPIO_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup GPIO_Private_Constants GPIO Private Constants + * @{ + */ + +#define GPIO_NUMBER 16U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup GPIO_Exported_Functions GPIO Exported Functions + * @{ + */ + +/** @defgroup GPIO_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to initialize and de-initialize the GPIOs + to be ready for use. + +@endverbatim + * @{ + */ + + +/** + * @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_Init. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains + * the configuration information for the specified GPIO peripheral. + * @retval None + */ +void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init) +{ + uint32_t position; + uint32_t ioposition = 0x00U; + uint32_t iocurrent = 0x00U; + uint32_t temp = 0x00U; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Init->Pin)); + assert_param(IS_GPIO_MODE(GPIO_Init->Mode)); + + /* Configure the port pins */ + for(position = 0U; position < GPIO_NUMBER; position++) + { + /* Get the IO position */ + ioposition = 0x01U << position; + /* Get the current IO position */ + iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; + + if(iocurrent == ioposition) + { + /*--------------------- GPIO Mode Configuration ------------------------*/ + /* In case of Output or Alternate function mode selection */ + if(((GPIO_Init->Mode & GPIO_MODE) == MODE_OUTPUT) || \ + (GPIO_Init->Mode & GPIO_MODE) == MODE_AF) + { + /* Check the Speed parameter */ + assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); + /* Configure the IO Speed */ + temp = GPIOx->OSPEEDR; + temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); + temp |= (GPIO_Init->Speed << (position * 2U)); + GPIOx->OSPEEDR = temp; + + /* Configure the IO Output Type */ + temp = GPIOx->OTYPER; + temp &= ~(GPIO_OTYPER_OT_0 << position) ; + temp |= (((GPIO_Init->Mode & OUTPUT_TYPE) >> OUTPUT_TYPE_Pos) << position); + GPIOx->OTYPER = temp; + } + + if((GPIO_Init->Mode & GPIO_MODE) != MODE_ANALOG) + { + /* Check the parameters */ + assert_param(IS_GPIO_PULL(GPIO_Init->Pull)); + + /* Activate the Pull-up or Pull down resistor for the current IO */ + temp = GPIOx->PUPDR; + temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); + temp |= ((GPIO_Init->Pull) << (position * 2U)); + GPIOx->PUPDR = temp; + } + + /* In case of Alternate function mode selection */ + if((GPIO_Init->Mode & GPIO_MODE) == MODE_AF) + { + /* Check the Alternate function parameter */ + assert_param(IS_GPIO_AF(GPIO_Init->Alternate)); + /* Configure Alternate function mapped with the current IO */ + temp = GPIOx->AFR[position >> 3U]; + temp &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; + temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & 0x07U) * 4U)); + GPIOx->AFR[position >> 3U] = temp; + } + + /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ + temp = GPIOx->MODER; + temp &= ~(GPIO_MODER_MODER0 << (position * 2U)); + temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2U)); + GPIOx->MODER = temp; + + /*--------------------- EXTI Mode Configuration ------------------------*/ + /* Configure the External Interrupt or event for the current IO */ + if((GPIO_Init->Mode & EXTI_MODE) != 0x00U) + { + /* Enable SYSCFG Clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + temp = SYSCFG->EXTICR[position >> 2U]; + temp &= ~(0x0FU << (4U * (position & 0x03U))); + temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U))); + SYSCFG->EXTICR[position >> 2U] = temp; + + /* Clear Rising Falling edge configuration */ + temp = EXTI->RTSR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & TRIGGER_RISING) != 0x00U) + { + temp |= iocurrent; + } + EXTI->RTSR = temp; + + temp = EXTI->FTSR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & TRIGGER_FALLING) != 0x00U) + { + temp |= iocurrent; + } + EXTI->FTSR = temp; + + temp = EXTI->EMR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & EXTI_EVT) != 0x00U) + { + temp |= iocurrent; + } + EXTI->EMR = temp; + + /* Clear EXTI line configuration */ + temp = EXTI->IMR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & EXTI_IT) != 0x00U) + { + temp |= iocurrent; + } + EXTI->IMR = temp; + } + } + } +} + +/** + * @brief De-initializes the GPIOx peripheral registers to their default reset values. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Pin specifies the port bit to be written. + * This parameter can be one of GPIO_PIN_x where x can be (0..15). + * @retval None + */ +void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin) +{ + uint32_t position; + uint32_t ioposition = 0x00U; + uint32_t iocurrent = 0x00U; + uint32_t tmp = 0x00U; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + + /* Configure the port pins */ + for(position = 0U; position < GPIO_NUMBER; position++) + { + /* Get the IO position */ + ioposition = 0x01U << position; + /* Get the current IO position */ + iocurrent = (GPIO_Pin) & ioposition; + + if(iocurrent == ioposition) + { + /*------------------------- EXTI Mode Configuration --------------------*/ + tmp = SYSCFG->EXTICR[position >> 2U]; + tmp &= (0x0FU << (4U * (position & 0x03U))); + if(tmp == ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U)))) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~((uint32_t)iocurrent); + EXTI->EMR &= ~((uint32_t)iocurrent); + + /* Clear Rising Falling edge configuration */ + EXTI->FTSR &= ~((uint32_t)iocurrent); + EXTI->RTSR &= ~((uint32_t)iocurrent); + + /* Configure the External Interrupt or event for the current IO */ + tmp = 0x0FU << (4U * (position & 0x03U)); + SYSCFG->EXTICR[position >> 2U] &= ~tmp; + } + + /*------------------------- GPIO Mode Configuration --------------------*/ + /* Configure IO Direction in Input Floating Mode */ + GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (position * 2U)); + + /* Configure the default Alternate Function in current IO */ + GPIOx->AFR[position >> 3U] &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; + + /* Deactivate the Pull-up and Pull-down resistor for the current IO */ + GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); + + /* Configure the default value IO Output Type */ + GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ; + + /* Configure the default value for IO Speed */ + GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); + } + } +} + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Functions_Group2 IO operation functions + * @brief GPIO Read and Write + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Reads the specified input port pin. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Pin specifies the port bit to read. + * This parameter can be GPIO_PIN_x where x can be (0..15). + * @retval The input port pin value. + */ +GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + GPIO_PinState bitstatus; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET) + { + bitstatus = GPIO_PIN_SET; + } + else + { + bitstatus = GPIO_PIN_RESET; + } + return bitstatus; +} + +/** + * @brief Sets or clears the selected data port bit. + * + * @note This function uses GPIOx_BSRR register to allow atomic read/modify + * accesses. In this way, there is no risk of an IRQ occurring between + * the read and the modify access. + * + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Pin specifies the port bit to be written. + * This parameter can be one of GPIO_PIN_x where x can be (0..15). + * @param PinState specifies the value to be written to the selected bit. + * This parameter can be one of the GPIO_PinState enum values: + * @arg GPIO_PIN_RESET: to clear the port pin + * @arg GPIO_PIN_SET: to set the port pin + * @retval None + */ +void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState) +{ + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_PIN_ACTION(PinState)); + + if(PinState != GPIO_PIN_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BSRR = (uint32_t)GPIO_Pin << 16U; + } +} + +/** + * @brief Toggles the specified GPIO pins. + * @param GPIOx Where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Pin Specifies the pins to be toggled. + * @retval None + */ +void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t odr; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + /* get current Output Data Register value */ + odr = GPIOx->ODR; + + /* Set selected pins that were at low level, and reset ones that were high */ + GPIOx->BSRR = ((odr & GPIO_Pin) << GPIO_NUMBER) | (~odr & GPIO_Pin); +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, + * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. + * @note The configuration of the locked GPIO pins can no longer be modified + * until the next reset. + * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F4 family + * @param GPIO_Pin specifies the port bit to be locked. + * This parameter can be any combination of GPIO_PIN_x where x can be (0..15). + * @retval None + */ +HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + __IO uint32_t tmp = GPIO_LCKR_LCKK; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + /* Apply lock key write sequence */ + tmp |= GPIO_Pin; + /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ + GPIOx->LCKR = tmp; + /* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ + GPIOx->LCKR = tmp; + /* Read LCKR register. This read is mandatory to complete key lock sequence */ + tmp = GPIOx->LCKR; + + /* Read again in order to confirm lock is active */ + if((GPIOx->LCKR & GPIO_LCKR_LCKK) != RESET) + { + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief This function handles EXTI interrupt request. + * @param GPIO_Pin Specifies the pins connected EXTI line + * @retval None + */ +void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) +{ + /* EXTI line interrupt detected */ + if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) + { + __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); + HAL_GPIO_EXTI_Callback(GPIO_Pin); + } +} + +/** + * @brief EXTI line detection callbacks. + * @param GPIO_Pin Specifies the pins connected EXTI line + * @retval None + */ +__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(GPIO_Pin); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_GPIO_EXTI_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + + +/** + * @} + */ + +#endif /* HAL_GPIO_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c index c2a8eb7..44487dc 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c @@ -1,7524 +1,7524 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c.c - * @author MCD Application Team - * @brief I2C HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Inter Integrated Circuit (I2C) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State, Mode and Error functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The I2C HAL driver can be used as follows: - - (#) Declare a I2C_HandleTypeDef handle structure, for example: - I2C_HandleTypeDef hi2c; - - (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API: - (##) Enable the I2Cx interface clock - (##) I2C pins configuration - (+++) Enable the clock for the I2C GPIOs - (+++) Configure I2C pins as alternate function open-drain - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the I2Cx interrupt priority - (+++) Enable the NVIC I2C IRQ Channel - (##) DMA Configuration if you need to use DMA process - (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream - (+++) Enable the DMAx interface clock using - (+++) Configure the DMA handle parameters - (+++) Configure the DMA Tx or Rx stream - (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on - the DMA Tx or Rx stream - - (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, - Dual Addressing mode, Own Address2, General call and Nostretch mode in the hi2c Init structure. - - (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware - (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit() API. - - (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady() - - (#) For I2C IO and IO MEM operations, three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit() - (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive() - (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit() - (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive() - - *** Polling mode IO MEM operation *** - ===================================== - [..] - (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write() - (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read() - - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT() - (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT() - (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT() - (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT() - (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - - *** Interrupt mode or DMA mode IO sequential operation *** - ========================================================== - [..] - (@) These interfaces allow to manage a sequential transfer with a repeated start condition - when a direction change during transfer - [..] - (+) A specific option field manage the different steps of a sequential transfer - (+) Option field values are defined through I2C_XferOptions_definition and are listed below: - (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode - (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition - (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition, an then permit a call the same master sequential interface - several times (like HAL_I2C_Master_Seq_Transmit_IT() then HAL_I2C_Master_Seq_Transmit_IT() - or HAL_I2C_Master_Seq_Transmit_DMA() then HAL_I2C_Master_Seq_Transmit_DMA()) - (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to transfer - if no direction change and without a final stop condition in both cases - (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to transfer - if no direction change and with a final stop condition in both cases - (++) I2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition after several call of the same master sequential - interface several times (link with option I2C_FIRST_AND_NEXT_FRAME). - Usage can, transfer several bytes one by one using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME). - Then usage of this option I2C_LAST_FRAME_NO_STOP at the last Transmit or Receive sequence permit to call the opposite interface Receive or Transmit - without stopping the communication and so generate a restart condition. - (++) I2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after each call of the same master sequential - interface. - Usage can, transfer several bytes one by one with a restart with slave address between each bytes using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME). - Then usage of this option I2C_OTHER_AND_LAST_FRAME at the last frame to help automatic generation of STOP condition. - - (+) Different sequential I2C interfaces are listed below: - (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Transmit_IT() - or using HAL_I2C_Master_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Receive_IT() - or using HAL_I2C_Master_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT() - (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can - add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). - (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_ListenCpltCallback() - (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Transmit_IT() - or using HAL_I2C_Slave_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Receive_IT() - or using HAL_I2C_Slave_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - *** Interrupt mode IO MEM operation *** - ======================================= - [..] - (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using - HAL_I2C_Mem_Write_IT() - (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using - HAL_I2C_Mem_Read_IT() - (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - *** DMA mode IO operation *** - ============================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Master_Transmit_DMA() - (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Master_Receive_DMA() - (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Slave_Transmit_DMA() - (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Slave_Receive_DMA() - (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - - *** DMA mode IO MEM operation *** - ================================= - [..] - (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using - HAL_I2C_Mem_Write_DMA() - (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using - HAL_I2C_Mem_Read_DMA() - (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - - *** I2C HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in I2C HAL driver. - - (+) __HAL_I2C_ENABLE: Enable the I2C peripheral - (+) __HAL_I2C_DISABLE: Disable the I2C peripheral - (+) __HAL_I2C_GET_FLAG: Checks whether the specified I2C flag is set or not - (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag - (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt - (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt - - *** Callback registration *** - ============================================= - [..] - The compilation flag USE_HAL_I2C_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_I2C_RegisterCallback() or HAL_I2C_RegisterAddrCallback() - to register an interrupt callback. - [..] - Function HAL_I2C_RegisterCallback() allows to register following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - For specific callback AddrCallback use dedicated register callbacks : HAL_I2C_RegisterAddrCallback(). - [..] - Use function HAL_I2C_UnRegisterCallback to reset a callback to the default - weak function. - HAL_I2C_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - [..] - For callback AddrCallback use dedicated register callbacks : HAL_I2C_UnRegisterAddrCallback(). - [..] - By default, after the HAL_I2C_Init() and when the state is HAL_I2C_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_I2C_MasterTxCpltCallback(), HAL_I2C_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_I2C_Init()/ HAL_I2C_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_I2C_Init()/ HAL_I2C_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - Callbacks can be registered/unregistered in HAL_I2C_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_I2C_STATE_READY or HAL_I2C_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_I2C_RegisterCallback() before calling HAL_I2C_DeInit() - or HAL_I2C_Init() function. - [..] - When the compilation flag USE_HAL_I2C_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - - - [..] - (@) You can refer to the I2C HAL driver header file for more useful macros - - @endverbatim - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup I2C I2C - * @brief I2C HAL module driver - * @{ - */ - -#ifdef HAL_I2C_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup I2C_Private_Define - * @{ - */ -#define I2C_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ -#define I2C_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ -#define I2C_TIMEOUT_STOP_FLAG 5U /*!< Timeout 5 ms */ -#define I2C_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ - -/* Private define for @ref PreviousState usage */ -#define I2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_I2C_STATE_BUSY_TX | (uint32_t)HAL_I2C_STATE_BUSY_RX) & (uint32_t)(~((uint32_t)HAL_I2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */ -#define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */ -#define I2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/** @defgroup I2C_Private_Functions I2C Private Functions - * @{ - */ -/* Private functions to handle DMA transfer */ -static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma); -static void I2C_DMAError(DMA_HandleTypeDef *hdma); -static void I2C_DMAAbort(DMA_HandleTypeDef *hdma); - -static void I2C_ITError(I2C_HandleTypeDef *hi2c); - -static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); - -/* Private functions to handle flags during polling transfer */ -static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c); -static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c); - -/* Private functions for I2C transfer IRQ handler */ -static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c); -static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c); -static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_Master_SB(I2C_HandleTypeDef *hi2c); -static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c); -static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c); - -static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags); -static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c); -static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c); - -static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c); - -/* Private function to Convert Specific options */ -static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Functions I2C Exported Functions - * @{ - */ - -/** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - deinitialize the I2Cx peripheral: - - (+) User must Implement HAL_I2C_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC). - - (+) Call the function HAL_I2C_Init() to configure the selected device with - the selected configuration: - (++) Communication Speed - (++) Duty cycle - (++) Addressing mode - (++) Own Address 1 - (++) Dual Addressing mode - (++) Own Address 2 - (++) General call mode - (++) Nostretch mode - - (+) Call the function HAL_I2C_DeInit() to restore the default configuration - of the selected I2Cx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the I2C according to the specified parameters - * in the I2C_InitTypeDef and initialize the associated handle. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c) -{ - uint32_t freqrange; - uint32_t pclk1; - - /* Check the I2C handle allocation */ - if (hi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_CLOCK_SPEED(hi2c->Init.ClockSpeed)); - assert_param(IS_I2C_DUTY_CYCLE(hi2c->Init.DutyCycle)); - assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1)); - assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode)); - assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode)); - assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2)); - assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode)); - assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode)); - - if (hi2c->State == HAL_I2C_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hi2c->Lock = HAL_UNLOCKED; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - /* Init the I2C Callback settings */ - hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ - hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ - - if (hi2c->MspInitCallback == NULL) - { - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - hi2c->MspInitCallback(hi2c); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_I2C_MspInit(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /*Reset I2C*/ - hi2c->Instance->CR1 |= I2C_CR1_SWRST; - hi2c->Instance->CR1 &= ~I2C_CR1_SWRST; - - /* Get PCLK1 frequency */ - pclk1 = HAL_RCC_GetPCLK1Freq(); - - /* Check the minimum allowed PCLK1 frequency */ - if (I2C_MIN_PCLK_FREQ(pclk1, hi2c->Init.ClockSpeed) == 1U) - { - return HAL_ERROR; - } - - /* Calculate frequency range */ - freqrange = I2C_FREQRANGE(pclk1); - - /*---------------------------- I2Cx CR2 Configuration ----------------------*/ - /* Configure I2Cx: Frequency range */ - MODIFY_REG(hi2c->Instance->CR2, I2C_CR2_FREQ, freqrange); - - /*---------------------------- I2Cx TRISE Configuration --------------------*/ - /* Configure I2Cx: Rise Time */ - MODIFY_REG(hi2c->Instance->TRISE, I2C_TRISE_TRISE, I2C_RISE_TIME(freqrange, hi2c->Init.ClockSpeed)); - - /*---------------------------- I2Cx CCR Configuration ----------------------*/ - /* Configure I2Cx: Speed */ - MODIFY_REG(hi2c->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), I2C_SPEED(pclk1, hi2c->Init.ClockSpeed, hi2c->Init.DutyCycle)); - - /*---------------------------- I2Cx CR1 Configuration ----------------------*/ - /* Configure I2Cx: Generalcall and NoStretch mode */ - MODIFY_REG(hi2c->Instance->CR1, (I2C_CR1_ENGC | I2C_CR1_NOSTRETCH), (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode)); - - /*---------------------------- I2Cx OAR1 Configuration ---------------------*/ - /* Configure I2Cx: Own Address1 and addressing mode */ - MODIFY_REG(hi2c->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hi2c->Init.AddressingMode | hi2c->Init.OwnAddress1)); - - /*---------------------------- I2Cx OAR2 Configuration ---------------------*/ - /* Configure I2Cx: Dual mode and Own Address2 */ - MODIFY_REG(hi2c->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2)); - - /* Enable the selected I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->Mode = HAL_I2C_MODE_NONE; - - return HAL_OK; -} - -/** - * @brief DeInitialize the I2C peripheral. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c) -{ - /* Check the I2C handle allocation */ - if (hi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the I2C Peripheral Clock */ - __HAL_I2C_DISABLE(hi2c); - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - if (hi2c->MspDeInitCallback == NULL) - { - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - hi2c->MspDeInitCallback(hi2c); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_I2C_MspDeInit(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->State = HAL_I2C_STATE_RESET; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; -} - -/** - * @brief Initialize the I2C MSP. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the I2C MSP. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User I2C Callback - * To be used instead of the weak predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : - hi2c->MasterTxCpltCallback = pCallback; - break; - - case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : - hi2c->MasterRxCpltCallback = pCallback; - break; - - case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : - hi2c->SlaveTxCpltCallback = pCallback; - break; - - case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : - hi2c->SlaveRxCpltCallback = pCallback; - break; - - case HAL_I2C_LISTEN_COMPLETE_CB_ID : - hi2c->ListenCpltCallback = pCallback; - break; - - case HAL_I2C_MEM_TX_COMPLETE_CB_ID : - hi2c->MemTxCpltCallback = pCallback; - break; - - case HAL_I2C_MEM_RX_COMPLETE_CB_ID : - hi2c->MemRxCpltCallback = pCallback; - break; - - case HAL_I2C_ERROR_CB_ID : - hi2c->ErrorCallback = pCallback; - break; - - case HAL_I2C_ABORT_CB_ID : - hi2c->AbortCpltCallback = pCallback; - break; - - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = pCallback; - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2C_STATE_RESET == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = pCallback; - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief Unregister an I2C Callback - * I2C callback is redirected to the weak predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * This parameter can be one of the following values: - * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : - hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - break; - - case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : - hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - break; - - case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : - hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - break; - - case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : - hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - break; - - case HAL_I2C_LISTEN_COMPLETE_CB_ID : - hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - break; - - case HAL_I2C_MEM_TX_COMPLETE_CB_ID : - hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - break; - - case HAL_I2C_MEM_RX_COMPLETE_CB_ID : - hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - break; - - case HAL_I2C_ERROR_CB_ID : - hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_I2C_ABORT_CB_ID : - hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2C_STATE_RESET == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief Register the Slave Address Match I2C Callback - * To be used instead of the weak HAL_I2C_AddrCallback() predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pCallback pointer to the Address Match Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - hi2c->AddrCallback = pCallback; - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief UnRegister the Slave Address Match I2C Callback - * Info Ready I2C Callback is redirected to the weak HAL_I2C_AddrCallback() predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the I2C data - transfers. - - (#) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_I2C_Master_Transmit() - (++) HAL_I2C_Master_Receive() - (++) HAL_I2C_Slave_Transmit() - (++) HAL_I2C_Slave_Receive() - (++) HAL_I2C_Mem_Write() - (++) HAL_I2C_Mem_Read() - (++) HAL_I2C_IsDeviceReady() - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_I2C_Master_Transmit_IT() - (++) HAL_I2C_Master_Receive_IT() - (++) HAL_I2C_Slave_Transmit_IT() - (++) HAL_I2C_Slave_Receive_IT() - (++) HAL_I2C_Mem_Write_IT() - (++) HAL_I2C_Mem_Read_IT() - (++) HAL_I2C_Master_Seq_Transmit_IT() - (++) HAL_I2C_Master_Seq_Receive_IT() - (++) HAL_I2C_Slave_Seq_Transmit_IT() - (++) HAL_I2C_Slave_Seq_Receive_IT() - (++) HAL_I2C_EnableListen_IT() - (++) HAL_I2C_DisableListen_IT() - (++) HAL_I2C_Master_Abort_IT() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_I2C_Master_Transmit_DMA() - (++) HAL_I2C_Master_Receive_DMA() - (++) HAL_I2C_Slave_Transmit_DMA() - (++) HAL_I2C_Slave_Receive_DMA() - (++) HAL_I2C_Mem_Write_DMA() - (++) HAL_I2C_Mem_Read_DMA() - (++) HAL_I2C_Master_Seq_Transmit_DMA() - (++) HAL_I2C_Master_Seq_Receive_DMA() - (++) HAL_I2C_Slave_Seq_Transmit_DMA() - (++) HAL_I2C_Slave_Seq_Receive_DMA() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_I2C_MasterTxCpltCallback() - (++) HAL_I2C_MasterRxCpltCallback() - (++) HAL_I2C_SlaveTxCpltCallback() - (++) HAL_I2C_SlaveRxCpltCallback() - (++) HAL_I2C_MemTxCpltCallback() - (++) HAL_I2C_MemRxCpltCallback() - (++) HAL_I2C_AddrCallback() - (++) HAL_I2C_ListenCpltCallback() - (++) HAL_I2C_ErrorCallback() - (++) HAL_I2C_AbortCpltCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmits in master mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address */ - if (I2C_MasterRequestWrite(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - } - - /* Wait until BTF flag is set */ - if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives in master mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address */ - if (I2C_MasterRequestRead(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hi2c->XferSize == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 2U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - if (hi2c->XferSize <= 3U) - { - /* One byte */ - if (hi2c->XferSize == 1U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* Two bytes */ - else if (hi2c->XferSize == 2U) - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* 3 Last bytes */ - else - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - else - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - } - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmits in slave mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* If 10bit addressing mode is selected */ - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT) - { - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - } - } - - /* Wait until AF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in blocking mode - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == (uint16_t)0)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - while (hi2c->XferSize > 0U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - - /* Wait until STOP flag is set */ - if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Clear STOP flag */ - __HAL_I2C_CLEAR_STOPFLAG(hi2c); - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in blocking mode to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - - /* Wait until BTF flag is set */ - if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in blocking mode from a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hi2c->XferSize == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 2U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - if (hi2c->XferSize <= 3U) - { - /* One byte */ - if (hi2c->XferSize == 1U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* Two bytes */ - else if (hi2c->XferSize == 2U) - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* 3 Last bytes */ - else - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - else - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - } - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - if (hi2c->XferSize > 0U) - { - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Abort the ongoing DMA */ - dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmatx); - - /* Prevent unused argument(s) compilation and MISRA warning */ - UNUSED(dmaxferstatus); - - /* Set the unused I2C DMA transfer complete callback to NULL */ - hi2c->hdmatx->XferCpltCallback = NULL; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferSize = 0U; - hi2c->XferCount = 0U; - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_SIZE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be read - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Abort the ongoing DMA */ - dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmarx); - - /* Prevent unused argument(s) compilation and MISRA warning */ - UNUSED(dmaxferstatus); - - /* Set the unused I2C DMA transfer complete callback to NULL */ - hi2c->hdmarx->XferCpltCallback = NULL; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferSize = 0U; - hi2c->XferCount = 0U; - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - return HAL_ERROR; - } - - if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Checks if target device is ready for communication. - * @note This function is used with Memory devices - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Trials Number of trials - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) -{ - /* Get tick */ - uint32_t tickstart = HAL_GetTick(); - uint32_t I2C_Trials = 0U; - FlagStatus tmp1; - FlagStatus tmp2; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - do - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR or AF flag are set */ - /* Get tick */ - tickstart = HAL_GetTick(); - - tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); - tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); - while ((hi2c->State != HAL_I2C_STATE_TIMEOUT) && (tmp1 == RESET) && (tmp2 == RESET)) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->State = HAL_I2C_STATE_TIMEOUT; - } - tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); - tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); - } - - hi2c->State = HAL_I2C_STATE_READY; - - /* Check if the ADDR flag has been set */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR) == SET) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear ADDR Flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear AF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - } - - /* Increment Trials */ - I2C_Trials++; - } - while (I2C_Trials < Trials); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0x00U; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with DMA. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0x00U; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ - /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ - if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0U; - uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) - { - if (Prev_State == I2C_STATE_MASTER_BUSY_RX) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Remove Enabling of IT_BUF, mean RXNE treatment, treat the 2 bytes through BTF */ - enableIT &= ~I2C_IT_BUF; - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable interrupts */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0U; - uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear Last DMA bit */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if (hi2c->XferSize > 0U) - { - if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) - { - if (Prev_State == I2C_STATE_MASTER_BUSY_RX) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_OTHER_AND_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - } - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - if (dmaxferstatus == HAL_OK) - { - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Update interrupt for only EVT and ERR */ - enableIT = (I2C_IT_EVT | I2C_IT_ERR); - } - else - { - /* Update interrupt for only ERR */ - enableIT = I2C_IT_ERR; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ - /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ - if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable interrupts */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Abort DMA Xfer if any */ - if (hi2c->hdmarx != NULL) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - } - else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - else - { - /* Nothing to do */ - } - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in slave mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in slave mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Abort DMA Xfer if any */ - if (hi2c->hdmarx != NULL) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - } - else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - else - { - /* Nothing to do */ - } - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Disable the Address listen mode with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of tmp to prevent undefined behavior of volatile usage */ - uint32_t tmp; - - /* Disable Address listen mode only if a transfer is not ongoing */ - if (hi2c->State == HAL_I2C_STATE_LISTEN) - { - tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK; - hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode); - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort a master I2C IT or DMA process communication with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(DevAddress); - - /* Abort Master transfer during Receive or Transmit process */ - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET) && (CurrentMode == HAL_I2C_MODE_MASTER)) - { - /* Process Locked */ - __HAL_LOCK(hi2c); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_ABORT; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->XferCount = 0U; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - I2C_ITError(hi2c); - - return HAL_OK; - } - else - { - /* Wrong usage of abort function */ - /* This function should be used only in case of abort monitored by master device */ - /* Or periphal is not in busy state, mean there is no active sequence to be abort */ - return HAL_ERROR; - } -} - -/** - * @} - */ - -/** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ - -/** - * @brief This function handles I2C event interrupt request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c) -{ - uint32_t sr1itflags; - uint32_t sr2itflags = 0U; - uint32_t itsources = READ_REG(hi2c->Instance->CR2); - uint32_t CurrentXferOptions = hi2c->XferOptions; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* Master or Memory mode selected */ - if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - sr1itflags = READ_REG(hi2c->Instance->SR1); - - /* Exit IRQ event until Start Bit detected in case of Other frame requested */ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) == RESET) && (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(CurrentXferOptions) == 1U)) - { - return; - } - - /* SB Set ----------------------------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - /* Convert OTHER_xxx XferOptions if any */ - I2C_ConvertOtherXferOptions(hi2c); - - I2C_Master_SB(hi2c); - } - /* ADD10 Set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADD10) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Master_ADD10(hi2c); - } - /* ADDR Set --------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Master_ADDR(hi2c); - } - /* I2C in mode Transmitter -----------------------------------------------*/ - else if (I2C_CHECK_FLAG(sr2itflags, I2C_FLAG_TRA) != RESET) - { - /* Do not check buffer and BTF flag if a Xfer DMA is on going */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_MasterTransmit_TXE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - if (CurrentState == HAL_I2C_STATE_BUSY_TX) - { - I2C_MasterTransmit_BTF(hi2c); - } - else /* HAL_I2C_MODE_MEM */ - { - if (CurrentMode == HAL_I2C_MODE_MEM) - { - I2C_MemoryTransmit_TXE_BTF(hi2c); - } - } - } - else - { - /* Do nothing */ - } - } - } - /* I2C in mode Receiver --------------------------------------------------*/ - else - { - /* Do not check buffer and BTF flag if a Xfer DMA is on going */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) - { - /* RXNE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_MasterReceive_RXNE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_MasterReceive_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - } - } - /* Slave mode selected */ - else - { - /* If an error is detected, read only SR1 register to prevent */ - /* a clear of ADDR flags by reading SR2 after reading SR1 in Error treatment */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - sr1itflags = READ_REG(hi2c->Instance->SR1); - } - else - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - sr1itflags = READ_REG(hi2c->Instance->SR1); - } - - /* ADDR set --------------------------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - /* Now time to read SR2, this will clear ADDR flag automatically */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - } - I2C_Slave_ADDR(hi2c, sr2itflags); - } - /* STOPF set --------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_STOPF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Slave_STOPF(hi2c); - } - /* I2C in mode Transmitter -----------------------------------------------*/ - else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_SlaveTransmit_TXE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_SlaveTransmit_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - /* I2C in mode Receiver --------------------------------------------------*/ - else - { - /* RXNE set and BTF reset ----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_SlaveReceive_RXNE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_SlaveReceive_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - } -} - -/** - * @brief This function handles I2C error interrupt request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c) -{ - HAL_I2C_ModeTypeDef tmp1; - uint32_t tmp2; - HAL_I2C_StateTypeDef tmp3; - uint32_t tmp4; - uint32_t sr1itflags = READ_REG(hi2c->Instance->SR1); - uint32_t itsources = READ_REG(hi2c->Instance->CR2); - uint32_t error = HAL_I2C_ERROR_NONE; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - - /* I2C Bus error interrupt occurred ----------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BERR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_BERR; - - /* Clear BERR flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR); - } - - /* I2C Arbitration Lost error interrupt occurred ---------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ARLO) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_ARLO; - - /* Clear ARLO flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO); - } - - /* I2C Acknowledge failure error interrupt occurred ------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_AF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - tmp1 = CurrentMode; - tmp2 = hi2c->XferCount; - tmp3 = hi2c->State; - tmp4 = hi2c->PreviousState; - if ((tmp1 == HAL_I2C_MODE_SLAVE) && (tmp2 == 0U) && \ - ((tmp3 == HAL_I2C_STATE_BUSY_TX) || (tmp3 == HAL_I2C_STATE_BUSY_TX_LISTEN) || \ - ((tmp3 == HAL_I2C_STATE_LISTEN) && (tmp4 == I2C_STATE_SLAVE_BUSY_TX)))) - { - I2C_Slave_AF(hi2c); - } - else - { - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - error |= HAL_I2C_ERROR_AF; - - /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ - if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - } - - /* I2C Over-Run/Under-Run interrupt occurred -------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_OVR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_OVR; - /* Clear OVR flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR); - } - - /* Call the Error Callback in case of Error detected -----------------------*/ - if (error != HAL_I2C_ERROR_NONE) - { - hi2c->ErrorCode |= error; - I2C_ITError(hi2c); - } -} - -/** - * @brief Master Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MasterTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Master Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MasterRxCpltCallback could be implemented in the user file - */ -} - -/** @brief Slave Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Address Match callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XferDirection_definition - * @param AddrMatchCode Address Match Code - * @retval None - */ -__weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - UNUSED(TransferDirection); - UNUSED(AddrMatchCode); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_AddrCallback() could be implemented in the user file - */ -} - -/** - * @brief Listen Complete callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_ListenCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Memory Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MemTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Memory Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MemRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief I2C error callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief I2C abort callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_AbortCpltCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @brief Peripheral State, Mode and Error functions - * -@verbatim - =============================================================================== - ##### Peripheral State, Mode and Error functions ##### - =============================================================================== - [..] - This subsection permit to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the I2C handle state. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL state - */ -HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c) -{ - /* Return I2C handle state */ - return hi2c->State; -} - -/** - * @brief Returns the I2C Master, Slave, Memory or no mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval HAL mode - */ -HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c) -{ - return hi2c->Mode; -} - -/** - * @brief Return the I2C error code. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval I2C Error Code - */ -uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c) -{ - return hi2c->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup I2C_Private_Functions - * @{ - */ - -/** - * @brief Handle TXE flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if ((hi2c->XferSize == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) - { - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || \ - ((CurrentMode == HAL_I2C_MODE_MEM) && (CurrentState == HAL_I2C_STATE_BUSY_RX))) - { - if (hi2c->XferCount == 0U) - { - /* Disable BUF interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - } - else - { - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - I2C_MemoryTransmit_TXE_BTF(hi2c); - } - else - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle BTF flag for Master transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (hi2c->State == HAL_I2C_STATE_BUSY_TX) - { - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) - { - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle TXE and BTF flag for Memory transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->EventCount == 0U) - { - /* If Memory address size is 8Bit */ - if (hi2c->MemaddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); - - hi2c->EventCount += 2U; - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(hi2c->Memaddress); - - hi2c->EventCount++; - } - } - else if (hi2c->EventCount == 1U) - { - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); - - hi2c->EventCount++; - } - else if (hi2c->EventCount == 2U) - { - if (CurrentState == HAL_I2C_STATE_BUSY_RX) - { - /* Generate Restart */ - hi2c->Instance->CR1 |= I2C_CR1_START; - - hi2c->EventCount++; - } - else if ((hi2c->XferCount > 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Generate Stop condition then Call TxCpltCallback() */ - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Do nothing */ - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle RXNE flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX) - { - uint32_t tmp; - - tmp = hi2c->XferCount; - if (tmp > 3U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if (hi2c->XferCount == (uint16_t)3) - { - /* Disable BUF interrupt, this help to treat correctly the last 4 bytes - on BTF subroutine */ - /* Disable BUF interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - } - } - else if ((hi2c->XferOptions != I2C_FIRST_AND_NEXT_FRAME) && ((tmp == 1U) || (tmp == 0U))) - { - if (I2C_WaitOnSTOPRequestThroughIT(hi2c) == HAL_OK) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call user error callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - } - } -} - -/** - * @brief Handle BTF flag for Master receiver - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (hi2c->XferCount == 4U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if (hi2c->XferCount == 3U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if (hi2c->XferCount == 2U) - { - /* Prepare next transfer or stop current transfer */ - if ((CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else if ((CurrentXferOptions == I2C_NEXT_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_NEXT_FRAME)) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else if (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else - { - /* Do nothing */ - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - hi2c->State = HAL_I2C_STATE_READY; - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle SB flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_SB(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - if (hi2c->EventCount == 0U) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); - } - else - { - hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); - } - } - else - { - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave 7 Bits address */ - if (hi2c->State == HAL_I2C_STATE_BUSY_TX) - { - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); - } - else - { - hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); - } - - if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) - || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - } - else - { - if (hi2c->EventCount == 0U) - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(hi2c->Devaddress); - } - else if (hi2c->EventCount == 1U) - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_READ(hi2c->Devaddress); - } - else - { - /* Do nothing */ - } - } - } -} - -/** - * @brief Handle ADD10 flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c) -{ - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(hi2c->Devaddress); - - if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) - || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } -} - -/** - * @brief Handle ADDR flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - uint32_t Prev_State = hi2c->PreviousState; - - if (hi2c->State == HAL_I2C_STATE_BUSY_RX) - { - if ((hi2c->EventCount == 0U) && (CurrentMode == HAL_I2C_MODE_MEM)) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else if ((hi2c->EventCount == 0U) && (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - hi2c->EventCount++; - } - else - { - if (hi2c->XferCount == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferCount == 1U) - { - if (CurrentXferOptions == I2C_NO_OPTION_FRAME) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - /* Prepare next transfer or stop current transfer */ - else if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) \ - && ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (CurrentXferOptions == I2C_FIRST_FRAME))) - { - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - else if (hi2c->XferCount == 2U) - { - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - /* Reset Event counter */ - hi2c->EventCount = 0U; - } - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } -} - -/** - * @brief Handle TXE flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) - { - /* Last Byte is received, disable Interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Handle BTF flag for Slave transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle RXNE flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->XferCount != 0U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) - { - /* Last Byte is received, disable Interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Handle BTF flag for Slave receiver - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->XferCount != 0U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle ADD flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param IT2Flags Interrupt2 flags to handle. - * @retval None - */ -static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags) -{ - uint8_t TransferDirection = I2C_DIRECTION_RECEIVE; - uint16_t SlaveAddrCode; - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* Disable BUF interrupt, BUF enabling is manage through slave specific interface */ - __HAL_I2C_DISABLE_IT(hi2c, (I2C_IT_BUF)); - - /* Transfer Direction requested by Master */ - if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_TRA) == RESET) - { - TransferDirection = I2C_DIRECTION_TRANSMIT; - } - - if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_DUALF) == RESET) - { - SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress1; - } - else - { - SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress2; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Call Slave Addr callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AddrCallback(hi2c, TransferDirection, SlaveAddrCode); -#else - HAL_I2C_AddrCallback(hi2c, TransferDirection, SlaveAddrCode); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - } -} - -/** - * @brief Handle STOPF flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear STOPF flag */ - __HAL_I2C_CLEAR_STOPFLAG(hi2c); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If a DMA is ongoing, Update handle size context */ - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - if ((CurrentState == HAL_I2C_STATE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) - { - hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmarx)); - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - - /* Disable, stop the current DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (HAL_DMA_GetState(hi2c->hdmarx) != HAL_DMA_STATE_READY) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - else - { - hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmatx)); - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - - /* Disable, stop the current DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (HAL_DMA_GetState(hi2c->hdmatx) != HAL_DMA_STATE_READY) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - - /* All data are not transferred, so set error code accordingly */ - if (hi2c->XferCount != 0U) - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - } - - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - I2C_ITError(hi2c); - } - else - { - if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - if (hi2c->State == HAL_I2C_STATE_LISTEN) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - if ((hi2c->PreviousState == I2C_STATE_SLAVE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } -} - -/** - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) && \ - (CurrentState == HAL_I2C_STATE_LISTEN)) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else if (CurrentState == HAL_I2C_STATE_BUSY_TX) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Clear AF flag only */ - /* State Listen, but XferOptions == FIRST or NEXT */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - } -} - -/** - * @brief I2C interrupts error process - * @param hi2c I2C handle. - * @retval None - */ -static void I2C_ITError(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentError; - - if (((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) && (CurrentState == HAL_I2C_STATE_BUSY_RX)) - { - /* Disable Pos bit in I2C CR1 when error occurred in Master/Mem Receive IT Process */ - hi2c->Instance->CR1 &= ~I2C_CR1_POS; - } - - if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* keep HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - } - else - { - /* If state is an abort treatment on going, don't change state */ - /* This change will be do later */ - if ((READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) && (CurrentState != HAL_I2C_STATE_ABORT)) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - } - hi2c->PreviousState = I2C_STATE_NONE; - } - - /* Abort DMA transfer */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - hi2c->Instance->CR2 &= ~I2C_CR2_DMAEN; - - if (hi2c->hdmatx->State != HAL_DMA_STATE_READY) - { - /* Set the DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - else - { - /* Set the DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - else if (hi2c->State == HAL_I2C_STATE_ABORT) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AbortCpltCallback(hi2c); -#else - HAL_I2C_AbortCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Call user error callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - /* STOP Flag is not set after a NACK reception, BusError, ArbitrationLost, OverRun */ - CurrentError = hi2c->ErrorCode; - - if (((CurrentError & HAL_I2C_ERROR_BERR) == HAL_I2C_ERROR_BERR) || \ - ((CurrentError & HAL_I2C_ERROR_ARLO) == HAL_I2C_ERROR_ARLO) || \ - ((CurrentError & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) || \ - ((CurrentError & HAL_I2C_ERROR_OVR) == HAL_I2C_ERROR_OVR)) - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - /* So may inform upper layer that listen phase is stopped */ - /* during NACK error treatment */ - CurrentState = hi2c->State; - if (((hi2c->ErrorCode & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) && (CurrentState == HAL_I2C_STATE_LISTEN)) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Generate Start condition if first transfer */ - if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) - { - /* Generate ReStart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Do nothing */ - } - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - } - else - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); - - /* Wait until ADD10 flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); - } - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address for read request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start condition if first transfer */ - if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) - { - /* Generate ReStart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Do nothing */ - } - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); - } - else - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); - - /* Wait until ADD10 flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_READ(DevAddress); - } - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for write request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) -{ - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for read request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) -{ - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief DMA I2C process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma) -{ - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - if ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_TX) == (uint32_t)HAL_I2C_STATE_BUSY_TX) || ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_RX) == (uint32_t)HAL_I2C_STATE_BUSY_RX) && (CurrentMode == HAL_I2C_MODE_SLAVE))) - { - /* Disable DMA Request */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - hi2c->XferCount = 0U; - - if (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Do nothing */ - } - - /* Enable EVT and ERR interrupt to treat end of transfer in IRQ handler */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - } - /* Check current Mode, in case of treatment DMA handler have been preempted by a prior interrupt */ - else if (hi2c->Mode != HAL_I2C_MODE_NONE) - { - if (hi2c->XferCount == (uint16_t)1) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Prepare next transfer or stop current transfer */ - if ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_OTHER_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - - /* Disable Last DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - - /* Disable DMA Request */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - hi2c->XferCount = 0U; - - /* Check if Errors has been detected during transfer */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief DMA I2C communication error callback. - * @param hdma DMA handle - * @retval None - */ -static void I2C_DMAError(DMA_HandleTypeDef *hdma) -{ - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - /* Ignore DMA FIFO error */ - if (HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) - { - /* Disable Acknowledge */ - hi2c->Instance->CR1 &= ~I2C_CR1_ACK; - - hi2c->XferCount = 0U; - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA I2C communication abort callback - * (To be called at end of DMA Abort procedure). - * @param hdma DMA handle. - * @retval None - */ -static void I2C_DMAAbort(DMA_HandleTypeDef *hdma) -{ - __IO uint32_t count = 0U; - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* During abort treatment, check that there is no pending STOP request */ - /* Wait until STOP flag is reset */ - count = I2C_TIMEOUT_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - if (count == 0U) - { - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - break; - } - count--; - } - while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferCount = 0U; - - /* Reset XferAbortCallback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferAbortCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferAbortCallback = NULL; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - /* Check if come from abort from user */ - if (hi2c->State == HAL_I2C_STATE_ABORT) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AbortCpltCallback(hi2c); -#else - HAL_I2C_AbortCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* Renable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* keep HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - } - else - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - } - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief This function handles I2C Communication Timeout. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param Flag specifies the I2C flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) -{ - /* Wait until flag is set */ - while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for Master addressing phase. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param Flag specifies the I2C flag to check. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, Flag) == RESET) - { - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear AF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of TXE flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of BTF flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of STOP flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of STOP request through Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c) -{ - __IO uint32_t count = 0U; - - /* Wait until STOP flag is reset */ - count = I2C_TIMEOUT_STOP_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - return HAL_ERROR; - } - } - while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); - - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) - { - /* Check if a STOPF is detected */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) - { - /* Clear STOP Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles Acknowledge failed detection during an I2C Communication. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c) -{ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) - { - /* Clear NACKF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - return HAL_OK; -} - -/** - * @brief Convert I2Cx OTHER_xxx XferOptions to functional XferOptions. - * @param hi2c I2C handle. - * @retval None - */ -static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c) -{ - /* if user set XferOptions to I2C_OTHER_FRAME */ - /* it request implicitly to generate a restart condition */ - /* set XferOptions to I2C_FIRST_FRAME */ - if (hi2c->XferOptions == I2C_OTHER_FRAME) - { - hi2c->XferOptions = I2C_FIRST_FRAME; - } - /* else if user set XferOptions to I2C_OTHER_AND_LAST_FRAME */ - /* it request implicitly to generate a restart condition */ - /* then generate a stop condition at the end of transfer */ - /* set XferOptions to I2C_FIRST_AND_LAST_FRAME */ - else if (hi2c->XferOptions == I2C_OTHER_AND_LAST_FRAME) - { - hi2c->XferOptions = I2C_FIRST_AND_LAST_FRAME; - } - else - { - /* Nothing to do */ - } -} - -/** - * @} - */ - -#endif /* HAL_I2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c.c + * @author MCD Application Team + * @brief I2C HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Inter Integrated Circuit (I2C) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State, Mode and Error functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The I2C HAL driver can be used as follows: + + (#) Declare a I2C_HandleTypeDef handle structure, for example: + I2C_HandleTypeDef hi2c; + + (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API: + (##) Enable the I2Cx interface clock + (##) I2C pins configuration + (+++) Enable the clock for the I2C GPIOs + (+++) Configure I2C pins as alternate function open-drain + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the I2Cx interrupt priority + (+++) Enable the NVIC I2C IRQ Channel + (##) DMA Configuration if you need to use DMA process + (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream + (+++) Enable the DMAx interface clock using + (+++) Configure the DMA handle parameters + (+++) Configure the DMA Tx or Rx stream + (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on + the DMA Tx or Rx stream + + (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, + Dual Addressing mode, Own Address2, General call and Nostretch mode in the hi2c Init structure. + + (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware + (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit() API. + + (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady() + + (#) For I2C IO and IO MEM operations, three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit() + (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive() + (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit() + (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive() + + *** Polling mode IO MEM operation *** + ===================================== + [..] + (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write() + (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read() + + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT() + (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT() + (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT() + (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT() + (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + + *** Interrupt mode or DMA mode IO sequential operation *** + ========================================================== + [..] + (@) These interfaces allow to manage a sequential transfer with a repeated start condition + when a direction change during transfer + [..] + (+) A specific option field manage the different steps of a sequential transfer + (+) Option field values are defined through I2C_XferOptions_definition and are listed below: + (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode + (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition + (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition, an then permit a call the same master sequential interface + several times (like HAL_I2C_Master_Seq_Transmit_IT() then HAL_I2C_Master_Seq_Transmit_IT() + or HAL_I2C_Master_Seq_Transmit_DMA() then HAL_I2C_Master_Seq_Transmit_DMA()) + (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to transfer + if no direction change and without a final stop condition in both cases + (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to transfer + if no direction change and with a final stop condition in both cases + (++) I2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition after several call of the same master sequential + interface several times (link with option I2C_FIRST_AND_NEXT_FRAME). + Usage can, transfer several bytes one by one using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME). + Then usage of this option I2C_LAST_FRAME_NO_STOP at the last Transmit or Receive sequence permit to call the opposite interface Receive or Transmit + without stopping the communication and so generate a restart condition. + (++) I2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after each call of the same master sequential + interface. + Usage can, transfer several bytes one by one with a restart with slave address between each bytes using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME). + Then usage of this option I2C_OTHER_AND_LAST_FRAME at the last frame to help automatic generation of STOP condition. + + (+) Different sequential I2C interfaces are listed below: + (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Transmit_IT() + or using HAL_I2C_Master_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Receive_IT() + or using HAL_I2C_Master_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT() + (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can + add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). + (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_ListenCpltCallback() + (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Transmit_IT() + or using HAL_I2C_Slave_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Receive_IT() + or using HAL_I2C_Slave_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + *** Interrupt mode IO MEM operation *** + ======================================= + [..] + (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using + HAL_I2C_Mem_Write_IT() + (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using + HAL_I2C_Mem_Read_IT() + (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Master_Transmit_DMA() + (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Master_Receive_DMA() + (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Slave_Transmit_DMA() + (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Slave_Receive_DMA() + (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + + *** DMA mode IO MEM operation *** + ================================= + [..] + (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using + HAL_I2C_Mem_Write_DMA() + (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using + HAL_I2C_Mem_Read_DMA() + (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + + *** I2C HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in I2C HAL driver. + + (+) __HAL_I2C_ENABLE: Enable the I2C peripheral + (+) __HAL_I2C_DISABLE: Disable the I2C peripheral + (+) __HAL_I2C_GET_FLAG: Checks whether the specified I2C flag is set or not + (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag + (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt + (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt + + *** Callback registration *** + ============================================= + [..] + The compilation flag USE_HAL_I2C_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_I2C_RegisterCallback() or HAL_I2C_RegisterAddrCallback() + to register an interrupt callback. + [..] + Function HAL_I2C_RegisterCallback() allows to register following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + For specific callback AddrCallback use dedicated register callbacks : HAL_I2C_RegisterAddrCallback(). + [..] + Use function HAL_I2C_UnRegisterCallback to reset a callback to the default + weak function. + HAL_I2C_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + [..] + For callback AddrCallback use dedicated register callbacks : HAL_I2C_UnRegisterAddrCallback(). + [..] + By default, after the HAL_I2C_Init() and when the state is HAL_I2C_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_I2C_MasterTxCpltCallback(), HAL_I2C_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_I2C_Init()/ HAL_I2C_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_I2C_Init()/ HAL_I2C_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + Callbacks can be registered/unregistered in HAL_I2C_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_I2C_STATE_READY or HAL_I2C_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_I2C_RegisterCallback() before calling HAL_I2C_DeInit() + or HAL_I2C_Init() function. + [..] + When the compilation flag USE_HAL_I2C_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + + + [..] + (@) You can refer to the I2C HAL driver header file for more useful macros + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup I2C I2C + * @brief I2C HAL module driver + * @{ + */ + +#ifdef HAL_I2C_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup I2C_Private_Define + * @{ + */ +#define I2C_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ +#define I2C_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ +#define I2C_TIMEOUT_STOP_FLAG 5U /*!< Timeout 5 ms */ +#define I2C_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ + +/* Private define for @ref PreviousState usage */ +#define I2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_I2C_STATE_BUSY_TX | (uint32_t)HAL_I2C_STATE_BUSY_RX) & (uint32_t)(~((uint32_t)HAL_I2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */ +#define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */ +#define I2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/** @defgroup I2C_Private_Functions I2C Private Functions + * @{ + */ +/* Private functions to handle DMA transfer */ +static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma); +static void I2C_DMAError(DMA_HandleTypeDef *hdma); +static void I2C_DMAAbort(DMA_HandleTypeDef *hdma); + +static void I2C_ITError(I2C_HandleTypeDef *hi2c); + +static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); + +/* Private functions to handle flags during polling transfer */ +static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c); +static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c); + +/* Private functions for I2C transfer IRQ handler */ +static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c); +static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c); +static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_Master_SB(I2C_HandleTypeDef *hi2c); +static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c); +static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c); + +static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags); +static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c); +static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c); + +static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c); + +/* Private function to Convert Specific options */ +static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup I2C_Exported_Functions I2C Exported Functions + * @{ + */ + +/** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + deinitialize the I2Cx peripheral: + + (+) User must Implement HAL_I2C_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC). + + (+) Call the function HAL_I2C_Init() to configure the selected device with + the selected configuration: + (++) Communication Speed + (++) Duty cycle + (++) Addressing mode + (++) Own Address 1 + (++) Dual Addressing mode + (++) Own Address 2 + (++) General call mode + (++) Nostretch mode + + (+) Call the function HAL_I2C_DeInit() to restore the default configuration + of the selected I2Cx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the I2C according to the specified parameters + * in the I2C_InitTypeDef and initialize the associated handle. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c) +{ + uint32_t freqrange; + uint32_t pclk1; + + /* Check the I2C handle allocation */ + if (hi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_CLOCK_SPEED(hi2c->Init.ClockSpeed)); + assert_param(IS_I2C_DUTY_CYCLE(hi2c->Init.DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1)); + assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode)); + assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode)); + assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2)); + assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode)); + assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode)); + + if (hi2c->State == HAL_I2C_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hi2c->Lock = HAL_UNLOCKED; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + /* Init the I2C Callback settings */ + hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ + hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ + + if (hi2c->MspInitCallback == NULL) + { + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + hi2c->MspInitCallback(hi2c); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_I2C_MspInit(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /*Reset I2C*/ + hi2c->Instance->CR1 |= I2C_CR1_SWRST; + hi2c->Instance->CR1 &= ~I2C_CR1_SWRST; + + /* Get PCLK1 frequency */ + pclk1 = HAL_RCC_GetPCLK1Freq(); + + /* Check the minimum allowed PCLK1 frequency */ + if (I2C_MIN_PCLK_FREQ(pclk1, hi2c->Init.ClockSpeed) == 1U) + { + return HAL_ERROR; + } + + /* Calculate frequency range */ + freqrange = I2C_FREQRANGE(pclk1); + + /*---------------------------- I2Cx CR2 Configuration ----------------------*/ + /* Configure I2Cx: Frequency range */ + MODIFY_REG(hi2c->Instance->CR2, I2C_CR2_FREQ, freqrange); + + /*---------------------------- I2Cx TRISE Configuration --------------------*/ + /* Configure I2Cx: Rise Time */ + MODIFY_REG(hi2c->Instance->TRISE, I2C_TRISE_TRISE, I2C_RISE_TIME(freqrange, hi2c->Init.ClockSpeed)); + + /*---------------------------- I2Cx CCR Configuration ----------------------*/ + /* Configure I2Cx: Speed */ + MODIFY_REG(hi2c->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), I2C_SPEED(pclk1, hi2c->Init.ClockSpeed, hi2c->Init.DutyCycle)); + + /*---------------------------- I2Cx CR1 Configuration ----------------------*/ + /* Configure I2Cx: Generalcall and NoStretch mode */ + MODIFY_REG(hi2c->Instance->CR1, (I2C_CR1_ENGC | I2C_CR1_NOSTRETCH), (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode)); + + /*---------------------------- I2Cx OAR1 Configuration ---------------------*/ + /* Configure I2Cx: Own Address1 and addressing mode */ + MODIFY_REG(hi2c->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hi2c->Init.AddressingMode | hi2c->Init.OwnAddress1)); + + /*---------------------------- I2Cx OAR2 Configuration ---------------------*/ + /* Configure I2Cx: Dual mode and Own Address2 */ + MODIFY_REG(hi2c->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2)); + + /* Enable the selected I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->Mode = HAL_I2C_MODE_NONE; + + return HAL_OK; +} + +/** + * @brief DeInitialize the I2C peripheral. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c) +{ + /* Check the I2C handle allocation */ + if (hi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the I2C Peripheral Clock */ + __HAL_I2C_DISABLE(hi2c); + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + if (hi2c->MspDeInitCallback == NULL) + { + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + hi2c->MspDeInitCallback(hi2c); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_I2C_MspDeInit(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->State = HAL_I2C_STATE_RESET; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; +} + +/** + * @brief Initialize the I2C MSP. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the I2C MSP. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User I2C Callback + * To be used instead of the weak predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : + hi2c->MasterTxCpltCallback = pCallback; + break; + + case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : + hi2c->MasterRxCpltCallback = pCallback; + break; + + case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : + hi2c->SlaveTxCpltCallback = pCallback; + break; + + case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : + hi2c->SlaveRxCpltCallback = pCallback; + break; + + case HAL_I2C_LISTEN_COMPLETE_CB_ID : + hi2c->ListenCpltCallback = pCallback; + break; + + case HAL_I2C_MEM_TX_COMPLETE_CB_ID : + hi2c->MemTxCpltCallback = pCallback; + break; + + case HAL_I2C_MEM_RX_COMPLETE_CB_ID : + hi2c->MemRxCpltCallback = pCallback; + break; + + case HAL_I2C_ERROR_CB_ID : + hi2c->ErrorCallback = pCallback; + break; + + case HAL_I2C_ABORT_CB_ID : + hi2c->AbortCpltCallback = pCallback; + break; + + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = pCallback; + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2C_STATE_RESET == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = pCallback; + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief Unregister an I2C Callback + * I2C callback is redirected to the weak predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * This parameter can be one of the following values: + * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : + hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + break; + + case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : + hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + break; + + case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : + hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + break; + + case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : + hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + break; + + case HAL_I2C_LISTEN_COMPLETE_CB_ID : + hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + break; + + case HAL_I2C_MEM_TX_COMPLETE_CB_ID : + hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + break; + + case HAL_I2C_MEM_RX_COMPLETE_CB_ID : + hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + break; + + case HAL_I2C_ERROR_CB_ID : + hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_I2C_ABORT_CB_ID : + hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2C_STATE_RESET == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief Register the Slave Address Match I2C Callback + * To be used instead of the weak HAL_I2C_AddrCallback() predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pCallback pointer to the Address Match Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + hi2c->AddrCallback = pCallback; + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief UnRegister the Slave Address Match I2C Callback + * Info Ready I2C Callback is redirected to the weak HAL_I2C_AddrCallback() predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the I2C data + transfers. + + (#) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_I2C_Master_Transmit() + (++) HAL_I2C_Master_Receive() + (++) HAL_I2C_Slave_Transmit() + (++) HAL_I2C_Slave_Receive() + (++) HAL_I2C_Mem_Write() + (++) HAL_I2C_Mem_Read() + (++) HAL_I2C_IsDeviceReady() + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_I2C_Master_Transmit_IT() + (++) HAL_I2C_Master_Receive_IT() + (++) HAL_I2C_Slave_Transmit_IT() + (++) HAL_I2C_Slave_Receive_IT() + (++) HAL_I2C_Mem_Write_IT() + (++) HAL_I2C_Mem_Read_IT() + (++) HAL_I2C_Master_Seq_Transmit_IT() + (++) HAL_I2C_Master_Seq_Receive_IT() + (++) HAL_I2C_Slave_Seq_Transmit_IT() + (++) HAL_I2C_Slave_Seq_Receive_IT() + (++) HAL_I2C_EnableListen_IT() + (++) HAL_I2C_DisableListen_IT() + (++) HAL_I2C_Master_Abort_IT() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_I2C_Master_Transmit_DMA() + (++) HAL_I2C_Master_Receive_DMA() + (++) HAL_I2C_Slave_Transmit_DMA() + (++) HAL_I2C_Slave_Receive_DMA() + (++) HAL_I2C_Mem_Write_DMA() + (++) HAL_I2C_Mem_Read_DMA() + (++) HAL_I2C_Master_Seq_Transmit_DMA() + (++) HAL_I2C_Master_Seq_Receive_DMA() + (++) HAL_I2C_Slave_Seq_Transmit_DMA() + (++) HAL_I2C_Slave_Seq_Receive_DMA() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_I2C_MasterTxCpltCallback() + (++) HAL_I2C_MasterRxCpltCallback() + (++) HAL_I2C_SlaveTxCpltCallback() + (++) HAL_I2C_SlaveRxCpltCallback() + (++) HAL_I2C_MemTxCpltCallback() + (++) HAL_I2C_MemRxCpltCallback() + (++) HAL_I2C_AddrCallback() + (++) HAL_I2C_ListenCpltCallback() + (++) HAL_I2C_ErrorCallback() + (++) HAL_I2C_AbortCpltCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmits in master mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address */ + if (I2C_MasterRequestWrite(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + } + + /* Wait until BTF flag is set */ + if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives in master mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address */ + if (I2C_MasterRequestRead(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hi2c->XferSize == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 2U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + if (hi2c->XferSize <= 3U) + { + /* One byte */ + if (hi2c->XferSize == 1U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* Two bytes */ + else if (hi2c->XferSize == 2U) + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* 3 Last bytes */ + else + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + else + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + } + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmits in slave mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* If 10bit addressing mode is selected */ + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT) + { + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + } + } + + /* Wait until AF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in blocking mode + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == (uint16_t)0)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + while (hi2c->XferSize > 0U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + + /* Wait until STOP flag is set */ + if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Clear STOP flag */ + __HAL_I2C_CLEAR_STOPFLAG(hi2c); + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in blocking mode to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + + /* Wait until BTF flag is set */ + if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in blocking mode from a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hi2c->XferSize == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 2U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + if (hi2c->XferSize <= 3U) + { + /* One byte */ + if (hi2c->XferSize == 1U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* Two bytes */ + else if (hi2c->XferSize == 2U) + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* 3 Last bytes */ + else + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + else + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + } + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + if (hi2c->XferSize > 0U) + { + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Abort the ongoing DMA */ + dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmatx); + + /* Prevent unused argument(s) compilation and MISRA warning */ + UNUSED(dmaxferstatus); + + /* Set the unused I2C DMA transfer complete callback to NULL */ + hi2c->hdmatx->XferCpltCallback = NULL; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferSize = 0U; + hi2c->XferCount = 0U; + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_SIZE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be read + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Abort the ongoing DMA */ + dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmarx); + + /* Prevent unused argument(s) compilation and MISRA warning */ + UNUSED(dmaxferstatus); + + /* Set the unused I2C DMA transfer complete callback to NULL */ + hi2c->hdmarx->XferCpltCallback = NULL; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferSize = 0U; + hi2c->XferCount = 0U; + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + return HAL_ERROR; + } + + if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Checks if target device is ready for communication. + * @note This function is used with Memory devices + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Trials Number of trials + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) +{ + /* Get tick */ + uint32_t tickstart = HAL_GetTick(); + uint32_t I2C_Trials = 0U; + FlagStatus tmp1; + FlagStatus tmp2; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + do + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR or AF flag are set */ + /* Get tick */ + tickstart = HAL_GetTick(); + + tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); + tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); + while ((hi2c->State != HAL_I2C_STATE_TIMEOUT) && (tmp1 == RESET) && (tmp2 == RESET)) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->State = HAL_I2C_STATE_TIMEOUT; + } + tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); + tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); + } + + hi2c->State = HAL_I2C_STATE_READY; + + /* Check if the ADDR flag has been set */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR) == SET) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear ADDR Flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear AF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + } + + /* Increment Trials */ + I2C_Trials++; + } + while (I2C_Trials < Trials); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0x00U; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with DMA. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0x00U; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ + /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ + if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0U; + uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) + { + if (Prev_State == I2C_STATE_MASTER_BUSY_RX) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Remove Enabling of IT_BUF, mean RXNE treatment, treat the 2 bytes through BTF */ + enableIT &= ~I2C_IT_BUF; + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable interrupts */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0U; + uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear Last DMA bit */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if (hi2c->XferSize > 0U) + { + if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) + { + if (Prev_State == I2C_STATE_MASTER_BUSY_RX) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_OTHER_AND_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + } + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + if (dmaxferstatus == HAL_OK) + { + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Update interrupt for only EVT and ERR */ + enableIT = (I2C_IT_EVT | I2C_IT_ERR); + } + else + { + /* Update interrupt for only ERR */ + enableIT = I2C_IT_ERR; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ + /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ + if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable interrupts */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Abort DMA Xfer if any */ + if (hi2c->hdmarx != NULL) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + } + else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + else + { + /* Nothing to do */ + } + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in slave mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in slave mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Abort DMA Xfer if any */ + if (hi2c->hdmarx != NULL) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + } + else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + else + { + /* Nothing to do */ + } + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Disable the Address listen mode with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of tmp to prevent undefined behavior of volatile usage */ + uint32_t tmp; + + /* Disable Address listen mode only if a transfer is not ongoing */ + if (hi2c->State == HAL_I2C_STATE_LISTEN) + { + tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK; + hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode); + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort a master I2C IT or DMA process communication with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(DevAddress); + + /* Abort Master transfer during Receive or Transmit process */ + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET) && (CurrentMode == HAL_I2C_MODE_MASTER)) + { + /* Process Locked */ + __HAL_LOCK(hi2c); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_ABORT; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->XferCount = 0U; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + I2C_ITError(hi2c); + + return HAL_OK; + } + else + { + /* Wrong usage of abort function */ + /* This function should be used only in case of abort monitored by master device */ + /* Or periphal is not in busy state, mean there is no active sequence to be abort */ + return HAL_ERROR; + } +} + +/** + * @} + */ + +/** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks + * @{ + */ + +/** + * @brief This function handles I2C event interrupt request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c) +{ + uint32_t sr1itflags; + uint32_t sr2itflags = 0U; + uint32_t itsources = READ_REG(hi2c->Instance->CR2); + uint32_t CurrentXferOptions = hi2c->XferOptions; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* Master or Memory mode selected */ + if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + sr1itflags = READ_REG(hi2c->Instance->SR1); + + /* Exit IRQ event until Start Bit detected in case of Other frame requested */ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) == RESET) && (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(CurrentXferOptions) == 1U)) + { + return; + } + + /* SB Set ----------------------------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + /* Convert OTHER_xxx XferOptions if any */ + I2C_ConvertOtherXferOptions(hi2c); + + I2C_Master_SB(hi2c); + } + /* ADD10 Set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADD10) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Master_ADD10(hi2c); + } + /* ADDR Set --------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Master_ADDR(hi2c); + } + /* I2C in mode Transmitter -----------------------------------------------*/ + else if (I2C_CHECK_FLAG(sr2itflags, I2C_FLAG_TRA) != RESET) + { + /* Do not check buffer and BTF flag if a Xfer DMA is on going */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_MasterTransmit_TXE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + if (CurrentState == HAL_I2C_STATE_BUSY_TX) + { + I2C_MasterTransmit_BTF(hi2c); + } + else /* HAL_I2C_MODE_MEM */ + { + if (CurrentMode == HAL_I2C_MODE_MEM) + { + I2C_MemoryTransmit_TXE_BTF(hi2c); + } + } + } + else + { + /* Do nothing */ + } + } + } + /* I2C in mode Receiver --------------------------------------------------*/ + else + { + /* Do not check buffer and BTF flag if a Xfer DMA is on going */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) + { + /* RXNE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_MasterReceive_RXNE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_MasterReceive_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + } + } + /* Slave mode selected */ + else + { + /* If an error is detected, read only SR1 register to prevent */ + /* a clear of ADDR flags by reading SR2 after reading SR1 in Error treatment */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + sr1itflags = READ_REG(hi2c->Instance->SR1); + } + else + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + sr1itflags = READ_REG(hi2c->Instance->SR1); + } + + /* ADDR set --------------------------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + /* Now time to read SR2, this will clear ADDR flag automatically */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + } + I2C_Slave_ADDR(hi2c, sr2itflags); + } + /* STOPF set --------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_STOPF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Slave_STOPF(hi2c); + } + /* I2C in mode Transmitter -----------------------------------------------*/ + else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_SlaveTransmit_TXE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_SlaveTransmit_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + /* I2C in mode Receiver --------------------------------------------------*/ + else + { + /* RXNE set and BTF reset ----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_SlaveReceive_RXNE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_SlaveReceive_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + } +} + +/** + * @brief This function handles I2C error interrupt request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c) +{ + HAL_I2C_ModeTypeDef tmp1; + uint32_t tmp2; + HAL_I2C_StateTypeDef tmp3; + uint32_t tmp4; + uint32_t sr1itflags = READ_REG(hi2c->Instance->SR1); + uint32_t itsources = READ_REG(hi2c->Instance->CR2); + uint32_t error = HAL_I2C_ERROR_NONE; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + + /* I2C Bus error interrupt occurred ----------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BERR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_BERR; + + /* Clear BERR flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR); + } + + /* I2C Arbitration Lost error interrupt occurred ---------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ARLO) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_ARLO; + + /* Clear ARLO flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO); + } + + /* I2C Acknowledge failure error interrupt occurred ------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_AF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + tmp1 = CurrentMode; + tmp2 = hi2c->XferCount; + tmp3 = hi2c->State; + tmp4 = hi2c->PreviousState; + if ((tmp1 == HAL_I2C_MODE_SLAVE) && (tmp2 == 0U) && \ + ((tmp3 == HAL_I2C_STATE_BUSY_TX) || (tmp3 == HAL_I2C_STATE_BUSY_TX_LISTEN) || \ + ((tmp3 == HAL_I2C_STATE_LISTEN) && (tmp4 == I2C_STATE_SLAVE_BUSY_TX)))) + { + I2C_Slave_AF(hi2c); + } + else + { + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + error |= HAL_I2C_ERROR_AF; + + /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ + if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + } + + /* I2C Over-Run/Under-Run interrupt occurred -------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_OVR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_OVR; + /* Clear OVR flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR); + } + + /* Call the Error Callback in case of Error detected -----------------------*/ + if (error != HAL_I2C_ERROR_NONE) + { + hi2c->ErrorCode |= error; + I2C_ITError(hi2c); + } +} + +/** + * @brief Master Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MasterTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Master Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MasterRxCpltCallback could be implemented in the user file + */ +} + +/** @brief Slave Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Address Match callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XferDirection_definition + * @param AddrMatchCode Address Match Code + * @retval None + */ +__weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + UNUSED(TransferDirection); + UNUSED(AddrMatchCode); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_AddrCallback() could be implemented in the user file + */ +} + +/** + * @brief Listen Complete callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_ListenCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Memory Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MemTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Memory Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MemRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief I2C error callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief I2C abort callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_AbortCpltCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions + * @brief Peripheral State, Mode and Error functions + * +@verbatim + =============================================================================== + ##### Peripheral State, Mode and Error functions ##### + =============================================================================== + [..] + This subsection permit to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the I2C handle state. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL state + */ +HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c) +{ + /* Return I2C handle state */ + return hi2c->State; +} + +/** + * @brief Returns the I2C Master, Slave, Memory or no mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval HAL mode + */ +HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c) +{ + return hi2c->Mode; +} + +/** + * @brief Return the I2C error code. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval I2C Error Code + */ +uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c) +{ + return hi2c->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup I2C_Private_Functions + * @{ + */ + +/** + * @brief Handle TXE flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if ((hi2c->XferSize == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) + { + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || \ + ((CurrentMode == HAL_I2C_MODE_MEM) && (CurrentState == HAL_I2C_STATE_BUSY_RX))) + { + if (hi2c->XferCount == 0U) + { + /* Disable BUF interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + } + else + { + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + I2C_MemoryTransmit_TXE_BTF(hi2c); + } + else + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle BTF flag for Master transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (hi2c->State == HAL_I2C_STATE_BUSY_TX) + { + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) + { + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle TXE and BTF flag for Memory transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->EventCount == 0U) + { + /* If Memory address size is 8Bit */ + if (hi2c->MemaddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); + + hi2c->EventCount += 2U; + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(hi2c->Memaddress); + + hi2c->EventCount++; + } + } + else if (hi2c->EventCount == 1U) + { + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); + + hi2c->EventCount++; + } + else if (hi2c->EventCount == 2U) + { + if (CurrentState == HAL_I2C_STATE_BUSY_RX) + { + /* Generate Restart */ + hi2c->Instance->CR1 |= I2C_CR1_START; + + hi2c->EventCount++; + } + else if ((hi2c->XferCount > 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Generate Stop condition then Call TxCpltCallback() */ + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Do nothing */ + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle RXNE flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX) + { + uint32_t tmp; + + tmp = hi2c->XferCount; + if (tmp > 3U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if (hi2c->XferCount == (uint16_t)3) + { + /* Disable BUF interrupt, this help to treat correctly the last 4 bytes + on BTF subroutine */ + /* Disable BUF interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + } + } + else if ((hi2c->XferOptions != I2C_FIRST_AND_NEXT_FRAME) && ((tmp == 1U) || (tmp == 0U))) + { + if (I2C_WaitOnSTOPRequestThroughIT(hi2c) == HAL_OK) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call user error callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + } + } +} + +/** + * @brief Handle BTF flag for Master receiver + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (hi2c->XferCount == 4U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if (hi2c->XferCount == 3U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if (hi2c->XferCount == 2U) + { + /* Prepare next transfer or stop current transfer */ + if ((CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else if ((CurrentXferOptions == I2C_NEXT_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_NEXT_FRAME)) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else if (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else + { + /* Do nothing */ + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + hi2c->State = HAL_I2C_STATE_READY; + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle SB flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_SB(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + if (hi2c->EventCount == 0U) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); + } + else + { + hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); + } + } + else + { + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave 7 Bits address */ + if (hi2c->State == HAL_I2C_STATE_BUSY_TX) + { + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); + } + else + { + hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); + } + + if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) + || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + } + else + { + if (hi2c->EventCount == 0U) + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(hi2c->Devaddress); + } + else if (hi2c->EventCount == 1U) + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_READ(hi2c->Devaddress); + } + else + { + /* Do nothing */ + } + } + } +} + +/** + * @brief Handle ADD10 flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c) +{ + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(hi2c->Devaddress); + + if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) + || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } +} + +/** + * @brief Handle ADDR flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + uint32_t Prev_State = hi2c->PreviousState; + + if (hi2c->State == HAL_I2C_STATE_BUSY_RX) + { + if ((hi2c->EventCount == 0U) && (CurrentMode == HAL_I2C_MODE_MEM)) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else if ((hi2c->EventCount == 0U) && (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + hi2c->EventCount++; + } + else + { + if (hi2c->XferCount == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferCount == 1U) + { + if (CurrentXferOptions == I2C_NO_OPTION_FRAME) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + /* Prepare next transfer or stop current transfer */ + else if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) \ + && ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (CurrentXferOptions == I2C_FIRST_FRAME))) + { + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + else if (hi2c->XferCount == 2U) + { + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + /* Reset Event counter */ + hi2c->EventCount = 0U; + } + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } +} + +/** + * @brief Handle TXE flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) + { + /* Last Byte is received, disable Interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Handle BTF flag for Slave transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle RXNE flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->XferCount != 0U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) + { + /* Last Byte is received, disable Interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Handle BTF flag for Slave receiver + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->XferCount != 0U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle ADD flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param IT2Flags Interrupt2 flags to handle. + * @retval None + */ +static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags) +{ + uint8_t TransferDirection = I2C_DIRECTION_RECEIVE; + uint16_t SlaveAddrCode; + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* Disable BUF interrupt, BUF enabling is manage through slave specific interface */ + __HAL_I2C_DISABLE_IT(hi2c, (I2C_IT_BUF)); + + /* Transfer Direction requested by Master */ + if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_TRA) == RESET) + { + TransferDirection = I2C_DIRECTION_TRANSMIT; + } + + if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_DUALF) == RESET) + { + SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress1; + } + else + { + SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress2; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Call Slave Addr callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AddrCallback(hi2c, TransferDirection, SlaveAddrCode); +#else + HAL_I2C_AddrCallback(hi2c, TransferDirection, SlaveAddrCode); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + } +} + +/** + * @brief Handle STOPF flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear STOPF flag */ + __HAL_I2C_CLEAR_STOPFLAG(hi2c); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If a DMA is ongoing, Update handle size context */ + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + if ((CurrentState == HAL_I2C_STATE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) + { + hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmarx)); + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + + /* Disable, stop the current DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (HAL_DMA_GetState(hi2c->hdmarx) != HAL_DMA_STATE_READY) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + else + { + hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmatx)); + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + + /* Disable, stop the current DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (HAL_DMA_GetState(hi2c->hdmatx) != HAL_DMA_STATE_READY) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + + /* All data are not transferred, so set error code accordingly */ + if (hi2c->XferCount != 0U) + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + } + + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + I2C_ITError(hi2c); + } + else + { + if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + if (hi2c->State == HAL_I2C_STATE_LISTEN) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + if ((hi2c->PreviousState == I2C_STATE_SLAVE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } +} + +/** + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) && \ + (CurrentState == HAL_I2C_STATE_LISTEN)) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else if (CurrentState == HAL_I2C_STATE_BUSY_TX) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Clear AF flag only */ + /* State Listen, but XferOptions == FIRST or NEXT */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + } +} + +/** + * @brief I2C interrupts error process + * @param hi2c I2C handle. + * @retval None + */ +static void I2C_ITError(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentError; + + if (((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) && (CurrentState == HAL_I2C_STATE_BUSY_RX)) + { + /* Disable Pos bit in I2C CR1 when error occurred in Master/Mem Receive IT Process */ + hi2c->Instance->CR1 &= ~I2C_CR1_POS; + } + + if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* keep HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + } + else + { + /* If state is an abort treatment on going, don't change state */ + /* This change will be do later */ + if ((READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) && (CurrentState != HAL_I2C_STATE_ABORT)) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + } + hi2c->PreviousState = I2C_STATE_NONE; + } + + /* Abort DMA transfer */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + hi2c->Instance->CR2 &= ~I2C_CR2_DMAEN; + + if (hi2c->hdmatx->State != HAL_DMA_STATE_READY) + { + /* Set the DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + else + { + /* Set the DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + else if (hi2c->State == HAL_I2C_STATE_ABORT) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AbortCpltCallback(hi2c); +#else + HAL_I2C_AbortCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Call user error callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + /* STOP Flag is not set after a NACK reception, BusError, ArbitrationLost, OverRun */ + CurrentError = hi2c->ErrorCode; + + if (((CurrentError & HAL_I2C_ERROR_BERR) == HAL_I2C_ERROR_BERR) || \ + ((CurrentError & HAL_I2C_ERROR_ARLO) == HAL_I2C_ERROR_ARLO) || \ + ((CurrentError & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) || \ + ((CurrentError & HAL_I2C_ERROR_OVR) == HAL_I2C_ERROR_OVR)) + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + /* So may inform upper layer that listen phase is stopped */ + /* during NACK error treatment */ + CurrentState = hi2c->State; + if (((hi2c->ErrorCode & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) && (CurrentState == HAL_I2C_STATE_LISTEN)) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Generate Start condition if first transfer */ + if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) + { + /* Generate ReStart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Do nothing */ + } + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + } + else + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); + + /* Wait until ADD10 flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); + } + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address for read request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start condition if first transfer */ + if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) + { + /* Generate ReStart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Do nothing */ + } + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); + } + else + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); + + /* Wait until ADD10 flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_READ(DevAddress); + } + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for write request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) +{ + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for read request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) +{ + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief DMA I2C process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma) +{ + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + if ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_TX) == (uint32_t)HAL_I2C_STATE_BUSY_TX) || ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_RX) == (uint32_t)HAL_I2C_STATE_BUSY_RX) && (CurrentMode == HAL_I2C_MODE_SLAVE))) + { + /* Disable DMA Request */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + hi2c->XferCount = 0U; + + if (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Do nothing */ + } + + /* Enable EVT and ERR interrupt to treat end of transfer in IRQ handler */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + } + /* Check current Mode, in case of treatment DMA handler have been preempted by a prior interrupt */ + else if (hi2c->Mode != HAL_I2C_MODE_NONE) + { + if (hi2c->XferCount == (uint16_t)1) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Prepare next transfer or stop current transfer */ + if ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_OTHER_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + + /* Disable Last DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + + /* Disable DMA Request */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + hi2c->XferCount = 0U; + + /* Check if Errors has been detected during transfer */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief DMA I2C communication error callback. + * @param hdma DMA handle + * @retval None + */ +static void I2C_DMAError(DMA_HandleTypeDef *hdma) +{ + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + /* Ignore DMA FIFO error */ + if (HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) + { + /* Disable Acknowledge */ + hi2c->Instance->CR1 &= ~I2C_CR1_ACK; + + hi2c->XferCount = 0U; + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA I2C communication abort callback + * (To be called at end of DMA Abort procedure). + * @param hdma DMA handle. + * @retval None + */ +static void I2C_DMAAbort(DMA_HandleTypeDef *hdma) +{ + __IO uint32_t count = 0U; + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* During abort treatment, check that there is no pending STOP request */ + /* Wait until STOP flag is reset */ + count = I2C_TIMEOUT_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + if (count == 0U) + { + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + break; + } + count--; + } + while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferCount = 0U; + + /* Reset XferAbortCallback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferAbortCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferAbortCallback = NULL; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + /* Check if come from abort from user */ + if (hi2c->State == HAL_I2C_STATE_ABORT) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AbortCpltCallback(hi2c); +#else + HAL_I2C_AbortCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* Renable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* keep HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + } + else + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + } + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief This function handles I2C Communication Timeout. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param Flag specifies the I2C flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) +{ + /* Wait until flag is set */ + while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for Master addressing phase. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param Flag specifies the I2C flag to check. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, Flag) == RESET) + { + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear AF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of TXE flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of BTF flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of STOP flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of STOP request through Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c) +{ + __IO uint32_t count = 0U; + + /* Wait until STOP flag is reset */ + count = I2C_TIMEOUT_STOP_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + return HAL_ERROR; + } + } + while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); + + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) + { + /* Check if a STOPF is detected */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) + { + /* Clear STOP Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles Acknowledge failed detection during an I2C Communication. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c) +{ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) + { + /* Clear NACKF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + return HAL_OK; +} + +/** + * @brief Convert I2Cx OTHER_xxx XferOptions to functional XferOptions. + * @param hi2c I2C handle. + * @retval None + */ +static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c) +{ + /* if user set XferOptions to I2C_OTHER_FRAME */ + /* it request implicitly to generate a restart condition */ + /* set XferOptions to I2C_FIRST_FRAME */ + if (hi2c->XferOptions == I2C_OTHER_FRAME) + { + hi2c->XferOptions = I2C_FIRST_FRAME; + } + /* else if user set XferOptions to I2C_OTHER_AND_LAST_FRAME */ + /* it request implicitly to generate a restart condition */ + /* then generate a stop condition at the end of transfer */ + /* set XferOptions to I2C_FIRST_AND_LAST_FRAME */ + else if (hi2c->XferOptions == I2C_OTHER_AND_LAST_FRAME) + { + hi2c->XferOptions = I2C_FIRST_AND_LAST_FRAME; + } + else + { + /* Nothing to do */ + } +} + +/** + * @} + */ + +#endif /* HAL_I2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c index 64aabaa..351f4fd 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c @@ -1,182 +1,182 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c_ex.c - * @author MCD Application Team - * @brief I2C Extension HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of I2C extension peripheral: - * + Extension features functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### I2C peripheral extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the I2C interface for STM32F427xx/437xx/ - 429xx/439xx devices contains the following additional features : - - (+) Possibility to disable or enable Analog Noise Filter - (+) Use of a configured Digital Noise Filter - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to configure Noise Filter - (#) Configure I2C Analog noise filter using the function HAL_I2C_AnalogFilter_Config() - (#) Configure I2C Digital noise filter using the function HAL_I2C_DigitalFilter_Config() - - @endverbatim - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup I2CEx I2CEx - * @brief I2C HAL module driver - * @{ - */ - -#ifdef HAL_I2C_MODULE_ENABLED - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup I2CEx_Exported_Functions I2C Exported Functions - * @{ - */ - - -/** @defgroup I2CEx_Exported_Functions_Group1 Extension features functions - * @brief Extension features functions - * -@verbatim - =============================================================================== - ##### Extension features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure Noise Filters - -@endverbatim - * @{ - */ - -/** - * @brief Configures I2C Analog noise filter. - * @param hi2c pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2Cx peripheral. - * @param AnalogFilter new state of the Analog filter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /* Reset I2Cx ANOFF bit */ - hi2c->Instance->FLTR &= ~(I2C_FLTR_ANOFF); - - /* Disable the analog filter */ - hi2c->Instance->FLTR |= AnalogFilter; - - __HAL_I2C_ENABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures I2C Digital noise filter. - * @param hi2c pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2Cx peripheral. - * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter) -{ - uint16_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /* Get the old register value */ - tmpreg = hi2c->Instance->FLTR; - - /* Reset I2Cx DNF bit [3:0] */ - tmpreg &= ~(I2C_FLTR_DNF); - - /* Set I2Cx DNF coefficient */ - tmpreg |= DigitalFilter; - - /* Store the new register value */ - hi2c->Instance->FLTR = tmpreg; - - __HAL_I2C_ENABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @} - */ - -/** - * @} - */ -#endif - -#endif /* HAL_I2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c_ex.c + * @author MCD Application Team + * @brief I2C Extension HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of I2C extension peripheral: + * + Extension features functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### I2C peripheral extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the I2C interface for STM32F427xx/437xx/ + 429xx/439xx devices contains the following additional features : + + (+) Possibility to disable or enable Analog Noise Filter + (+) Use of a configured Digital Noise Filter + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to configure Noise Filter + (#) Configure I2C Analog noise filter using the function HAL_I2C_AnalogFilter_Config() + (#) Configure I2C Digital noise filter using the function HAL_I2C_DigitalFilter_Config() + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup I2CEx I2CEx + * @brief I2C HAL module driver + * @{ + */ + +#ifdef HAL_I2C_MODULE_ENABLED + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup I2CEx_Exported_Functions I2C Exported Functions + * @{ + */ + + +/** @defgroup I2CEx_Exported_Functions_Group1 Extension features functions + * @brief Extension features functions + * +@verbatim + =============================================================================== + ##### Extension features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure Noise Filters + +@endverbatim + * @{ + */ + +/** + * @brief Configures I2C Analog noise filter. + * @param hi2c pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2Cx peripheral. + * @param AnalogFilter new state of the Analog filter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /* Reset I2Cx ANOFF bit */ + hi2c->Instance->FLTR &= ~(I2C_FLTR_ANOFF); + + /* Disable the analog filter */ + hi2c->Instance->FLTR |= AnalogFilter; + + __HAL_I2C_ENABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures I2C Digital noise filter. + * @param hi2c pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2Cx peripheral. + * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /* Get the old register value */ + tmpreg = hi2c->Instance->FLTR; + + /* Reset I2Cx DNF bit [3:0] */ + tmpreg &= ~(I2C_FLTR_DNF); + + /* Set I2Cx DNF coefficient */ + tmpreg |= DigitalFilter; + + /* Store the new register value */ + hi2c->Instance->FLTR = tmpreg; + + __HAL_I2C_ENABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @} + */ + +/** + * @} + */ +#endif + +#endif /* HAL_I2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c new file mode 100644 index 0000000..542bee5 --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c @@ -0,0 +1,262 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_iwdg.c + * @author MCD Application Team + * @brief IWDG HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Independent Watchdog (IWDG) peripheral: + * + Initialization and Start functions + * + IO operation functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### IWDG Generic features ##### + ============================================================================== + [..] + (+) The IWDG can be started by either software or hardware (configurable + through option byte). + + (+) The IWDG is clocked by the Low-Speed Internal clock (LSI) and thus stays + active even if the main clock fails. + + (+) Once the IWDG is started, the LSI is forced ON and both cannot be + disabled. The counter starts counting down from the reset value (0xFFF). + When it reaches the end of count value (0x000) a reset signal is + generated (IWDG reset). + + (+) Whenever the key value 0x0000 AAAA is written in the IWDG_KR register, + the IWDG_RLR value is reloaded into the counter and the watchdog reset + is prevented. + + (+) The IWDG is implemented in the VDD voltage domain that is still functional + in STOP and STANDBY mode (IWDG reset can wake up the CPU from STANDBY). + IWDGRST flag in RCC_CSR register can be used to inform when an IWDG + reset occurs. + + (+) Debug mode: When the microcontroller enters debug mode (core halted), + the IWDG counter either continues to work normally or stops, depending + on DBG_IWDG_STOP configuration bit in DBG module, accessible through + __HAL_DBGMCU_FREEZE_IWDG() and __HAL_DBGMCU_UNFREEZE_IWDG() macros. + + [..] Min-max timeout value @32KHz (LSI): ~125us / ~32.7s + The IWDG timeout may vary due to LSI clock frequency dispersion. + STM32F4xx devices provide the capability to measure the LSI clock + frequency (LSI clock is internally connected to TIM5 CH4 input capture). + The measured value can be used to have an IWDG timeout with an + acceptable accuracy. + + [..] Default timeout value (necessary for IWDG_SR status register update): + Constant LSI_VALUE is defined based on the nominal LSI clock frequency. + This frequency being subject to variations as mentioned above, the + default timeout value (defined through constant HAL_IWDG_DEFAULT_TIMEOUT + below) may become too short or too long. + In such cases, this default timeout value can be tuned by redefining + the constant LSI_VALUE at user-application level (based, for instance, + on the measured LSI clock frequency as explained above). + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Use IWDG using HAL_IWDG_Init() function to : + (++) Enable instance by writing Start keyword in IWDG_KEY register. LSI + clock is forced ON and IWDG counter starts counting down. + (++) Enable write access to configuration registers: + IWDG_PR and IWDG_RLR. + (++) Configure the IWDG prescaler and counter reload value. This reload + value will be loaded in the IWDG counter each time the watchdog is + reloaded, then the IWDG will start counting down from this value. + (++) Wait for status flags to be reset. + + (#) Then the application program must refresh the IWDG counter at regular + intervals during normal operation to prevent an MCU reset, using + HAL_IWDG_Refresh() function. + + *** IWDG HAL driver macros list *** + ==================================== + [..] + Below the list of most used macros in IWDG HAL driver: + (+) __HAL_IWDG_START: Enable the IWDG peripheral + (+) __HAL_IWDG_RELOAD_COUNTER: Reloads IWDG counter with value defined in + the reload register + + @endverbatim + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_IWDG_MODULE_ENABLED +/** @addtogroup IWDG + * @brief IWDG HAL module driver. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup IWDG_Private_Defines IWDG Private Defines + * @{ + */ +/* Status register needs up to 5 LSI clock periods divided by the clock + prescaler to be updated. The number of LSI clock periods is upper-rounded to + 6 for the timeout value calculation. + The timeout value is calculated using the highest prescaler (256) and + the LSI_VALUE constant. The value of this constant can be changed by the user + to take into account possible LSI clock period variations. + The timeout value is multiplied by 1000 to be converted in milliseconds. + LSI startup time is also considered here by adding LSI_STARTUP_TIME + converted in milliseconds. */ +#define HAL_IWDG_DEFAULT_TIMEOUT (((6UL * 256UL * 1000UL) / LSI_VALUE) + ((LSI_STARTUP_TIME / 1000UL) + 1UL)) +#define IWDG_KERNEL_UPDATE_FLAGS (IWDG_SR_RVU | IWDG_SR_PVU) +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup IWDG_Exported_Functions + * @{ + */ + +/** @addtogroup IWDG_Exported_Functions_Group1 + * @brief Initialization and Start functions. + * +@verbatim + =============================================================================== + ##### Initialization and Start functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the IWDG according to the specified parameters in the + IWDG_InitTypeDef of associated handle. + (+) Once initialization is performed in HAL_IWDG_Init function, Watchdog + is reloaded in order to exit function with correct time base. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the IWDG according to the specified parameters in the + * IWDG_InitTypeDef and start watchdog. Before exiting function, + * watchdog is refreshed in order to have correct time base. + * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains + * the configuration information for the specified IWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg) +{ + uint32_t tickstart; + + /* Check the IWDG handle allocation */ + if (hiwdg == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_IWDG_ALL_INSTANCE(hiwdg->Instance)); + assert_param(IS_IWDG_PRESCALER(hiwdg->Init.Prescaler)); + assert_param(IS_IWDG_RELOAD(hiwdg->Init.Reload)); + + /* Enable IWDG. LSI is turned on automatically */ + __HAL_IWDG_START(hiwdg); + + /* Enable write access to IWDG_PR and IWDG_RLR registers by writing + 0x5555 in KR */ + IWDG_ENABLE_WRITE_ACCESS(hiwdg); + + /* Write to IWDG registers the Prescaler & Reload values to work with */ + hiwdg->Instance->PR = hiwdg->Init.Prescaler; + hiwdg->Instance->RLR = hiwdg->Init.Reload; + + /* Check pending flag, if previous update not done, return timeout */ + tickstart = HAL_GetTick(); + + /* Wait for register to be updated */ + while ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) + { + if ((HAL_GetTick() - tickstart) > HAL_IWDG_DEFAULT_TIMEOUT) + { + if ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) + { + return HAL_TIMEOUT; + } + } + } + + /* Reload IWDG counter with value defined in the reload register */ + __HAL_IWDG_RELOAD_COUNTER(hiwdg); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @} + */ + + +/** @addtogroup IWDG_Exported_Functions_Group2 + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Refresh the IWDG. + +@endverbatim + * @{ + */ + +/** + * @brief Refresh the IWDG. + * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains + * the configuration information for the specified IWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg) +{ + /* Reload IWDG counter with value defined in the reload register */ + __HAL_IWDG_RELOAD_COUNTER(hiwdg); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_IWDG_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c index 7e46592..c8649ca 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c @@ -1,2387 +1,2387 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd.c - * @author MCD Application Team - * @brief PCD HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The PCD HAL driver can be used as follows: - - (#) Declare a PCD_HandleTypeDef handle structure, for example: - PCD_HandleTypeDef hpcd; - - (#) Fill parameters of Init structure in HCD handle - - (#) Call HAL_PCD_Init() API to initialize the PCD peripheral (Core, Device core, ...) - - (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API: - (##) Enable the PCD/USB Low Level interface clock using - (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) - - (##) Initialize the related GPIO clocks - (##) Configure PCD pin-out - (##) Configure PCD NVIC interrupt - - (#)Associate the Upper USB device stack to the HAL PCD Driver: - (##) hpcd.pData = pdev; - - (#)Enable PCD transmission and reception: - (##) HAL_PCD_Start(); - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PCD PCD - * @brief PCD HAL module driver - * @{ - */ - -#ifdef HAL_PCD_MODULE_ENABLED - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PCD_Private_Macros PCD Private Macros - * @{ - */ -#define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b)) -#define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b)) -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup PCD_Private_Functions PCD Private Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum); -static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); -static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PCD_Exported_Functions PCD Exported Functions - * @{ - */ - -/** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the PCD according to the specified - * parameters in the PCD_InitTypeDef and initialize the associated handle. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx; - uint8_t i; - - /* Check the PCD handle allocation */ - if (hpcd == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance)); - - USBx = hpcd->Instance; - - if (hpcd->State == HAL_PCD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hpcd->Lock = HAL_UNLOCKED; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SOFCallback = HAL_PCD_SOFCallback; - hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; - hpcd->ResetCallback = HAL_PCD_ResetCallback; - hpcd->SuspendCallback = HAL_PCD_SuspendCallback; - hpcd->ResumeCallback = HAL_PCD_ResumeCallback; - hpcd->ConnectCallback = HAL_PCD_ConnectCallback; - hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; - hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; - hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; - hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; - hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; - hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; - hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; - - if (hpcd->MspInitCallback == NULL) - { - hpcd->MspInitCallback = HAL_PCD_MspInit; - } - - /* Init the low level hardware */ - hpcd->MspInitCallback(hpcd); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - HAL_PCD_MspInit(hpcd); -#endif /* (USE_HAL_PCD_REGISTER_CALLBACKS) */ - } - - hpcd->State = HAL_PCD_STATE_BUSY; - - /* Disable DMA mode for FS instance */ - if ((USBx->CID & (0x1U << 8)) == 0U) - { - hpcd->Init.dma_enable = 0U; - } - - /* Disable the Interrupts */ - __HAL_PCD_DISABLE(hpcd); - - /*Init the Core (common init.) */ - if (USB_CoreInit(hpcd->Instance, hpcd->Init) != HAL_OK) - { - hpcd->State = HAL_PCD_STATE_ERROR; - return HAL_ERROR; - } - - /* Force Device Mode*/ - (void)USB_SetCurrentMode(hpcd->Instance, USB_DEVICE_MODE); - - /* Init endpoints structures */ - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - /* Init ep structure */ - hpcd->IN_ep[i].is_in = 1U; - hpcd->IN_ep[i].num = i; - hpcd->IN_ep[i].tx_fifo_num = i; - /* Control until ep is activated */ - hpcd->IN_ep[i].type = EP_TYPE_CTRL; - hpcd->IN_ep[i].maxpacket = 0U; - hpcd->IN_ep[i].xfer_buff = 0U; - hpcd->IN_ep[i].xfer_len = 0U; - } - - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - hpcd->OUT_ep[i].is_in = 0U; - hpcd->OUT_ep[i].num = i; - /* Control until ep is activated */ - hpcd->OUT_ep[i].type = EP_TYPE_CTRL; - hpcd->OUT_ep[i].maxpacket = 0U; - hpcd->OUT_ep[i].xfer_buff = 0U; - hpcd->OUT_ep[i].xfer_len = 0U; - } - - /* Init Device */ - if (USB_DevInit(hpcd->Instance, hpcd->Init) != HAL_OK) - { - hpcd->State = HAL_PCD_STATE_ERROR; - return HAL_ERROR; - } - - hpcd->USB_Address = 0U; - hpcd->State = HAL_PCD_STATE_READY; -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Activate LPM */ - if (hpcd->Init.lpm_enable == 1U) - { - (void)HAL_PCDEx_ActivateLPM(hpcd); - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - (void)USB_DevDisconnect(hpcd->Instance); - - return HAL_OK; -} - -/** - * @brief DeInitializes the PCD peripheral. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd) -{ - /* Check the PCD handle allocation */ - if (hpcd == NULL) - { - return HAL_ERROR; - } - - hpcd->State = HAL_PCD_STATE_BUSY; - - /* Stop Device */ - if (USB_StopDevice(hpcd->Instance) != HAL_OK) - { - return HAL_ERROR; - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - if (hpcd->MspDeInitCallback == NULL) - { - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hpcd->MspDeInitCallback(hpcd); -#else - /* DeInit the low level hardware: CLOCK, NVIC.*/ - HAL_PCD_MspDeInit(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - hpcd->State = HAL_PCD_STATE_RESET; - - return HAL_OK; -} - -/** - * @brief Initializes the PCD MSP. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes PCD MSP. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User USB PCD Callback - * To be used instead of the weak predefined callback - * @param hpcd USB PCD handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID - * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID - * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID - * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID - * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID - * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID - * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID - * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID, - pPCD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_PCD_SOF_CB_ID : - hpcd->SOFCallback = pCallback; - break; - - case HAL_PCD_SETUPSTAGE_CB_ID : - hpcd->SetupStageCallback = pCallback; - break; - - case HAL_PCD_RESET_CB_ID : - hpcd->ResetCallback = pCallback; - break; - - case HAL_PCD_SUSPEND_CB_ID : - hpcd->SuspendCallback = pCallback; - break; - - case HAL_PCD_RESUME_CB_ID : - hpcd->ResumeCallback = pCallback; - break; - - case HAL_PCD_CONNECT_CB_ID : - hpcd->ConnectCallback = pCallback; - break; - - case HAL_PCD_DISCONNECT_CB_ID : - hpcd->DisconnectCallback = pCallback; - break; - - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = pCallback; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hpcd->State == HAL_PCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = pCallback; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - return status; -} - -/** - * @brief Unregister an USB PCD Callback - * USB PCD callback is redirected to the weak predefined callback - * @param hpcd USB PCD handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID - * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID - * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID - * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID - * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID - * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID - * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID - * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - /* Setup Legacy weak Callbacks */ - if (hpcd->State == HAL_PCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_PCD_SOF_CB_ID : - hpcd->SOFCallback = HAL_PCD_SOFCallback; - break; - - case HAL_PCD_SETUPSTAGE_CB_ID : - hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; - break; - - case HAL_PCD_RESET_CB_ID : - hpcd->ResetCallback = HAL_PCD_ResetCallback; - break; - - case HAL_PCD_SUSPEND_CB_ID : - hpcd->SuspendCallback = HAL_PCD_SuspendCallback; - break; - - case HAL_PCD_RESUME_CB_ID : - hpcd->ResumeCallback = HAL_PCD_ResumeCallback; - break; - - case HAL_PCD_CONNECT_CB_ID : - hpcd->ConnectCallback = HAL_PCD_ConnectCallback; - break; - - case HAL_PCD_DISCONNECT_CB_ID : - hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; - break; - - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = HAL_PCD_MspInit; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hpcd->State == HAL_PCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = HAL_PCD_MspInit; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - return status; -} - -/** - * @brief Register USB PCD Data OUT Stage Callback - * To be used instead of the weak HAL_PCD_DataOutStageCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Data OUT Stage Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataOutStageCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataOutStageCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Data OUT Stage Callback - * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataOutStageCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; /* Legacy weak DataOutStageCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Data IN Stage Callback - * To be used instead of the weak HAL_PCD_DataInStageCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Data IN Stage Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataInStageCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataInStageCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Data IN Stage Callback - * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataInStageCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; /* Legacy weak DataInStageCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Iso OUT incomplete Callback - * To be used instead of the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Iso OUT incomplete Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoOutIncpltCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOOUTIncompleteCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Iso OUT incomplete Callback - * USB PCD Iso OUT incomplete Callback is redirected - * to the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; /* Legacy weak ISOOUTIncompleteCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Iso IN incomplete Callback - * To be used instead of the weak HAL_PCD_ISOINIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Iso IN incomplete Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoInIncpltCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOINIncompleteCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Iso IN incomplete Callback - * USB PCD Iso IN incomplete Callback is redirected - * to the weak HAL_PCD_ISOINIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; /* Legacy weak ISOINIncompleteCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD BCD Callback - * To be used instead of the weak HAL_PCDEx_BCD_Callback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD BCD Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->BCDCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD BCD Callback - * USB BCD Callback is redirected to the weak HAL_PCDEx_BCD_Callback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; /* Legacy weak HAL_PCDEx_BCD_Callback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD LPM Callback - * To be used instead of the weak HAL_PCDEx_LPM_Callback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD LPM Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->LPMCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD LPM Callback - * USB LPM Callback is redirected to the weak HAL_PCDEx_LPM_Callback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; /* Legacy weak HAL_PCDEx_LPM_Callback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the PCD data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Start the USB device - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Enable USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - - __HAL_PCD_ENABLE(hpcd); - (void)USB_DevConnect(hpcd->Instance); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Stop the USB device. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - __HAL_PCD_DISABLE(hpcd); - (void)USB_DevDisconnect(hpcd->Instance); - - (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Disable USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Handles PCD interrupt request. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - USB_OTG_EPTypeDef *ep; - uint32_t i; - uint32_t ep_intr; - uint32_t epint; - uint32_t epnum; - uint32_t fifoemptymsk; - uint32_t RegVal; - - /* ensure that we are in device mode */ - if (USB_GetMode(hpcd->Instance) == USB_OTG_MODE_DEVICE) - { - /* avoid spurious interrupt */ - if (__HAL_PCD_IS_INVALID_INTERRUPT(hpcd)) - { - return; - } - - /* store current frame number */ - hpcd->FrameNumber = (USBx_DEVICE->DSTS & USB_OTG_DSTS_FNSOF_Msk) >> USB_OTG_DSTS_FNSOF_Pos; - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_MMIS)) - { - /* incorrect mode, acknowledge the interrupt */ - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_MMIS); - } - - /* Handle RxQLevel Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_RXFLVL)) - { - USB_MASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); - - RegVal = USBx->GRXSTSP; - - ep = &hpcd->OUT_ep[RegVal & USB_OTG_GRXSTSP_EPNUM]; - - if (((RegVal & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) - { - if ((RegVal & USB_OTG_GRXSTSP_BCNT) != 0U) - { - (void)USB_ReadPacket(USBx, ep->xfer_buff, - (uint16_t)((RegVal & USB_OTG_GRXSTSP_BCNT) >> 4)); - - ep->xfer_buff += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; - ep->xfer_count += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; - } - } - else if (((RegVal & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) - { - (void)USB_ReadPacket(USBx, (uint8_t *)hpcd->Setup, 8U); - ep->xfer_count += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; - } - else - { - /* ... */ - } - - USB_UNMASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); - } - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OEPINT)) - { - epnum = 0U; - - /* Read in the device interrupt bits */ - ep_intr = USB_ReadDevAllOutEpInterrupt(hpcd->Instance); - - while (ep_intr != 0U) - { - if ((ep_intr & 0x1U) != 0U) - { - epint = USB_ReadDevOutEPInterrupt(hpcd->Instance, (uint8_t)epnum); - - if ((epint & USB_OTG_DOEPINT_XFRC) == USB_OTG_DOEPINT_XFRC) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_XFRC); - (void)PCD_EP_OutXfrComplete_int(hpcd, epnum); - } - - if ((epint & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STUP); - /* Class B setup phase done for previous decoded setup */ - (void)PCD_EP_OutSetupPacket_int(hpcd, epnum); - } - - if ((epint & USB_OTG_DOEPINT_OTEPDIS) == USB_OTG_DOEPINT_OTEPDIS) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPDIS); - } - - /* Clear OUT Endpoint disable interrupt */ - if ((epint & USB_OTG_DOEPINT_EPDISD) == USB_OTG_DOEPINT_EPDISD) - { - if ((USBx->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF) == USB_OTG_GINTSTS_BOUTNAKEFF) - { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK; - } - - ep = &hpcd->OUT_ep[epnum]; - - if (ep->is_iso_incomplete == 1U) - { - ep->is_iso_incomplete = 0U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_EPDISD); - } - - /* Clear Status Phase Received interrupt */ - if ((epint & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - - /* Clear OUT NAK interrupt */ - if ((epint & USB_OTG_DOEPINT_NAK) == USB_OTG_DOEPINT_NAK) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_NAK); - } - } - epnum++; - ep_intr >>= 1U; - } - } - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IEPINT)) - { - /* Read in the device interrupt bits */ - ep_intr = USB_ReadDevAllInEpInterrupt(hpcd->Instance); - - epnum = 0U; - - while (ep_intr != 0U) - { - if ((ep_intr & 0x1U) != 0U) /* In ITR */ - { - epint = USB_ReadDevInEPInterrupt(hpcd->Instance, (uint8_t)epnum); - - if ((epint & USB_OTG_DIEPINT_XFRC) == USB_OTG_DIEPINT_XFRC) - { - fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); - USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; - - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_XFRC); - - if (hpcd->Init.dma_enable == 1U) - { - hpcd->IN_ep[epnum].xfer_buff += hpcd->IN_ep[epnum].maxpacket; - - /* this is ZLP, so prepare EP0 for next setup */ - if ((epnum == 0U) && (hpcd->IN_ep[epnum].xfer_len == 0U)) - { - /* prepare to rx more setup packets */ - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataInStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataInStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - if ((epint & USB_OTG_DIEPINT_TOC) == USB_OTG_DIEPINT_TOC) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_TOC); - } - if ((epint & USB_OTG_DIEPINT_ITTXFE) == USB_OTG_DIEPINT_ITTXFE) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_ITTXFE); - } - if ((epint & USB_OTG_DIEPINT_INEPNE) == USB_OTG_DIEPINT_INEPNE) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_INEPNE); - } - if ((epint & USB_OTG_DIEPINT_EPDISD) == USB_OTG_DIEPINT_EPDISD) - { - (void)USB_FlushTxFifo(USBx, epnum); - - ep = &hpcd->IN_ep[epnum]; - - if (ep->is_iso_incomplete == 1U) - { - ep->is_iso_incomplete = 0U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ISOINIncompleteCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_ISOINIncompleteCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_EPDISD); - } - if ((epint & USB_OTG_DIEPINT_TXFE) == USB_OTG_DIEPINT_TXFE) - { - (void)PCD_WriteEmptyTxFifo(hpcd, epnum); - } - } - epnum++; - ep_intr >>= 1U; - } - } - - /* Handle Resume Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT)) - { - /* Clear the Remote Wake-up Signaling */ - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; - - if (hpcd->LPM_State == LPM_L1) - { - hpcd->LPM_State = LPM_L0; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->LPMCallback(hpcd, PCD_LPM_L0_ACTIVE); -#else - HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L0_ACTIVE); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ResumeCallback(hpcd); -#else - HAL_PCD_ResumeCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT); - } - - /* Handle Suspend Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP)) - { - if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SuspendCallback(hpcd); -#else - HAL_PCD_SuspendCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP); - } -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Handle LPM Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT)) - { - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT); - - if (hpcd->LPM_State == LPM_L0) - { - hpcd->LPM_State = LPM_L1; - hpcd->BESL = (hpcd->Instance->GLPMCFG & USB_OTG_GLPMCFG_BESL) >> 2U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->LPMCallback(hpcd, PCD_LPM_L1_ACTIVE); -#else - HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L1_ACTIVE); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SuspendCallback(hpcd); -#else - HAL_PCD_SuspendCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - /* Handle Reset Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBRST)) - { - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; - (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); - - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - USBx_INEP(i)->DIEPINT = 0xFB7FU; - USBx_INEP(i)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - USBx_OUTEP(i)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - USBx_OUTEP(i)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - } - USBx_DEVICE->DAINTMSK |= 0x10001U; - - if (hpcd->Init.use_dedicated_ep1 != 0U) - { - USBx_DEVICE->DOUTEP1MSK |= USB_OTG_DOEPMSK_STUPM | - USB_OTG_DOEPMSK_XFRCM | - USB_OTG_DOEPMSK_EPDM; - - USBx_DEVICE->DINEP1MSK |= USB_OTG_DIEPMSK_TOM | - USB_OTG_DIEPMSK_XFRCM | - USB_OTG_DIEPMSK_EPDM; - } - else - { - USBx_DEVICE->DOEPMSK |= USB_OTG_DOEPMSK_STUPM | - USB_OTG_DOEPMSK_XFRCM | - USB_OTG_DOEPMSK_EPDM | - USB_OTG_DOEPMSK_OTEPSPRM | - USB_OTG_DOEPMSK_NAKM; - - USBx_DEVICE->DIEPMSK |= USB_OTG_DIEPMSK_TOM | - USB_OTG_DIEPMSK_XFRCM | - USB_OTG_DIEPMSK_EPDM; - } - - /* Set Default Address to 0 */ - USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; - - /* setup EP0 to receive SETUP packets */ - (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, - (uint8_t *)hpcd->Setup); - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBRST); - } - - /* Handle Enumeration done Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE)) - { - (void)USB_ActivateSetup(hpcd->Instance); - hpcd->Init.speed = USB_GetDevSpeed(hpcd->Instance); - - /* Set USB Turnaround time */ - (void)USB_SetTurnaroundTime(hpcd->Instance, - HAL_RCC_GetHCLKFreq(), - (uint8_t)hpcd->Init.speed); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ResetCallback(hpcd); -#else - HAL_PCD_ResetCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE); - } - - /* Handle SOF Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SOF)) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SOFCallback(hpcd); -#else - HAL_PCD_SOFCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SOF); - } - - /* Handle Global OUT NAK effective Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_BOUTNAKEFF)) - { - USBx->GINTMSK &= ~USB_OTG_GINTMSK_GONAKEFFM; - - for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) - { - if (hpcd->OUT_ep[epnum].is_iso_incomplete == 1U) - { - /* Abort current transaction and disable the EP */ - (void)HAL_PCD_EP_Abort(hpcd, (uint8_t)epnum); - } - } - } - - /* Handle Incomplete ISO IN Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR)) - { - for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) - { - RegVal = USBx_INEP(epnum)->DIEPCTL; - - if ((hpcd->IN_ep[epnum].type == EP_TYPE_ISOC) && - ((RegVal & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA)) - { - hpcd->IN_ep[epnum].is_iso_incomplete = 1U; - - /* Abort current transaction and disable the EP */ - (void)HAL_PCD_EP_Abort(hpcd, (uint8_t)(epnum | 0x80U)); - } - } - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR); - } - - /* Handle Incomplete ISO OUT Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) - { - for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) - { - RegVal = USBx_OUTEP(epnum)->DOEPCTL; - - if ((hpcd->OUT_ep[epnum].type == EP_TYPE_ISOC) && - ((RegVal & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) && - ((RegVal & (0x1U << 16)) == (hpcd->FrameNumber & 0x1U))) - { - hpcd->OUT_ep[epnum].is_iso_incomplete = 1U; - - USBx->GINTMSK |= USB_OTG_GINTMSK_GONAKEFFM; - - if ((USBx->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF) == 0U) - { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SGONAK; - break; - } - } - } - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); - } - - /* Handle Connection event Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT)) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ConnectCallback(hpcd); -#else - HAL_PCD_ConnectCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT); - } - - /* Handle Disconnection event Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OTGINT)) - { - RegVal = hpcd->Instance->GOTGINT; - - if ((RegVal & USB_OTG_GOTGINT_SEDET) == USB_OTG_GOTGINT_SEDET) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DisconnectCallback(hpcd); -#else - HAL_PCD_DisconnectCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - hpcd->Instance->GOTGINT |= RegVal; - } - } -} - - -/** - * @brief Handles PCD Wakeup interrupt request. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx; - - USBx = hpcd->Instance; - - if ((USBx->CID & (0x1U << 8)) == 0U) - { - /* Clear EXTI pending Bit */ - __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG(); - } - else - { - /* Clear EXTI pending Bit */ - __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG(); - } -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @brief Data OUT stage callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DataOutStageCallback could be implemented in the user file - */ -} - -/** - * @brief Data IN stage callback - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DataInStageCallback could be implemented in the user file - */ -} -/** - * @brief Setup stage callback - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SetupStageCallback could be implemented in the user file - */ -} - -/** - * @brief USB Start Of Frame callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SOFCallback could be implemented in the user file - */ -} - -/** - * @brief USB Reset callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ResetCallback could be implemented in the user file - */ -} - -/** - * @brief Suspend event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SuspendCallback could be implemented in the user file - */ -} - -/** - * @brief Resume event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ResumeCallback could be implemented in the user file - */ -} - -/** - * @brief Incomplete ISO OUT callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file - */ -} - -/** - * @brief Incomplete ISO IN callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file - */ -} - -/** - * @brief Connection event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ConnectCallback could be implemented in the user file - */ -} - -/** - * @brief Disconnection event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DisconnectCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions - * @brief management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the PCD data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Connect the USB device - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Enable USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - (void)USB_DevConnect(hpcd->Instance); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Disconnect the USB device. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - (void)USB_DevDisconnect(hpcd->Instance); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Disable USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Set the USB Device address. - * @param hpcd PCD handle - * @param address new device address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address) -{ - __HAL_LOCK(hpcd); - hpcd->USB_Address = address; - (void)USB_SetDevAddress(hpcd->Instance, address); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} -/** - * @brief Open and configure an endpoint. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param ep_mps endpoint max packet size - * @param ep_type endpoint type - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint16_t ep_mps, uint8_t ep_type) -{ - HAL_StatusTypeDef ret = HAL_OK; - PCD_EPTypeDef *ep; - - if ((ep_addr & 0x80U) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - - ep->num = ep_addr & EP_ADDR_MSK; - ep->maxpacket = ep_mps; - ep->type = ep_type; - - if (ep->is_in != 0U) - { - /* Assign a Tx FIFO */ - ep->tx_fifo_num = ep->num; - } - /* Set initial data PID. */ - if (ep_type == EP_TYPE_BULK) - { - ep->data_pid_start = 0U; - } - - __HAL_LOCK(hpcd); - (void)USB_ActivateEndpoint(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - - return ret; -} - -/** - * @brief Deactivate an endpoint. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if ((ep_addr & 0x80U) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - (void)USB_DeactivateEndpoint(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - return HAL_OK; -} - - -/** - * @brief Receive an amount of data. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param pBuf pointer to the reception buffer - * @param len amount of data to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) -{ - PCD_EPTypeDef *ep; - - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - - /*setup and start the Xfer */ - ep->xfer_buff = pBuf; - ep->xfer_len = len; - ep->xfer_count = 0U; - ep->is_in = 0U; - ep->num = ep_addr & EP_ADDR_MSK; - - if (hpcd->Init.dma_enable == 1U) - { - ep->dma_addr = (uint32_t)pBuf; - } - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - else - { - (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - - return HAL_OK; -} - -/** - * @brief Get Received Data Size - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval Data Size - */ -uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - return hpcd->OUT_ep[ep_addr & EP_ADDR_MSK].xfer_count; -} -/** - * @brief Send an amount of data - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param pBuf pointer to the transmission buffer - * @param len amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) -{ - PCD_EPTypeDef *ep; - - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - - /*setup and start the Xfer */ - ep->xfer_buff = pBuf; - ep->xfer_len = len; - ep->xfer_count = 0U; - ep->is_in = 1U; - ep->num = ep_addr & EP_ADDR_MSK; - - if (hpcd->Init.dma_enable == 1U) - { - ep->dma_addr = (uint32_t)pBuf; - } - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - else - { - (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - - return HAL_OK; -} - -/** - * @brief Set a STALL condition over an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if (((uint32_t)ep_addr & EP_ADDR_MSK) > hpcd->Init.dev_endpoints) - { - return HAL_ERROR; - } - - if ((0x80U & ep_addr) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr]; - ep->is_in = 0U; - } - - ep->is_stall = 1U; - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - - (void)USB_EPSetStall(hpcd->Instance, ep); - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Clear a STALL condition over in an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if (((uint32_t)ep_addr & 0x0FU) > hpcd->Init.dev_endpoints) - { - return HAL_ERROR; - } - - if ((0x80U & ep_addr) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - - ep->is_stall = 0U; - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - (void)USB_EPClearStall(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Abort an USB EP transaction. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Abort(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - HAL_StatusTypeDef ret; - PCD_EPTypeDef *ep; - - if ((0x80U & ep_addr) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - } - - /* Stop Xfer */ - ret = USB_EPStopXfer(hpcd->Instance, ep); - - return ret; -} - -/** - * @brief Flush an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - __HAL_LOCK(hpcd); - - if ((ep_addr & 0x80U) == 0x80U) - { - (void)USB_FlushTxFifo(hpcd->Instance, (uint32_t)ep_addr & EP_ADDR_MSK); - } - else - { - (void)USB_FlushRxFifo(hpcd->Instance); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Activate remote wakeup signalling - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) -{ - return (USB_ActivateRemoteWakeup(hpcd->Instance)); -} - -/** - * @brief De-activate remote wakeup signalling. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) -{ - return (USB_DeActivateRemoteWakeup(hpcd->Instance)); -} - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the PCD handle state. - * @param hpcd PCD handle - * @retval HAL state - */ -PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd) -{ - return hpcd->State; -} - -/** - * @brief Set the USB Device high speed test mode. - * @param hpcd PCD handle - * @param testmode USB Device high speed test mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_SetTestMode(PCD_HandleTypeDef *hpcd, uint8_t testmode) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - - switch (testmode) - { - case TEST_J: - case TEST_K: - case TEST_SE0_NAK: - case TEST_PACKET: - case TEST_FORCE_EN: - USBx_DEVICE->DCTL |= (uint32_t)testmode << 4; - break; - - default: - break; - } - - return HAL_OK; -} -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup PCD_Private_Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Check FIFO for the next packet to be loaded. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - USB_OTG_EPTypeDef *ep; - uint32_t len; - uint32_t len32b; - uint32_t fifoemptymsk; - - ep = &hpcd->IN_ep[epnum]; - - if (ep->xfer_count > ep->xfer_len) - { - return HAL_ERROR; - } - - len = ep->xfer_len - ep->xfer_count; - - if (len > ep->maxpacket) - { - len = ep->maxpacket; - } - - len32b = (len + 3U) / 4U; - - while (((USBx_INEP(epnum)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= len32b) && - (ep->xfer_count < ep->xfer_len) && (ep->xfer_len != 0U)) - { - /* Write the FIFO */ - len = ep->xfer_len - ep->xfer_count; - - if (len > ep->maxpacket) - { - len = ep->maxpacket; - } - len32b = (len + 3U) / 4U; - - (void)USB_WritePacket(USBx, ep->xfer_buff, (uint8_t)epnum, (uint16_t)len, - (uint8_t)hpcd->Init.dma_enable); - - ep->xfer_buff += len; - ep->xfer_count += len; - } - - if (ep->xfer_len <= ep->xfer_count) - { - fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); - USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; - } - - return HAL_OK; -} - - -/** - * @brief process EP OUT transfer complete interrupt. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_EPTypeDef *ep; - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; - - if (hpcd->Init.dma_enable == 1U) - { - if ((DoepintReg & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) /* Class C */ - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - } - else if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) /* Class E */ - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - else if ((DoepintReg & (USB_OTG_DOEPINT_STUP | USB_OTG_DOEPINT_OTEPSPR)) == 0U) - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - else - { - ep = &hpcd->OUT_ep[epnum]; - - /* out data packet received over EP */ - ep->xfer_count = ep->xfer_size - (USBx_OUTEP(epnum)->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ); - - if (epnum == 0U) - { - if (ep->xfer_len == 0U) - { - /* this is ZLP, so prepare EP0 for next setup */ - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } - else - { - ep->xfer_buff += ep->xfer_count; - } - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - else - { - /* ... */ - } - } - else - { - if (gSNPSiD == USB_OTG_CORE_ID_310A) - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - else - { - if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - else - { - if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) - { - /* this is ZLP, so prepare EP0 for next setup */ - (void)USB_EP0_OutStart(hpcd->Instance, 0U, (uint8_t *)hpcd->Setup); - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - - return HAL_OK; -} - - -/** - * @brief process EP OUT setup packet received interrupt. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; - - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - - /* Inform the upper layer that a setup packet is available */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SetupStageCallback(hpcd); -#else - HAL_PCD_SetupStageCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && (hpcd->Init.dma_enable == 1U)) - { - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } - - return HAL_OK; -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* HAL_PCD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd.c + * @author MCD Application Team + * @brief PCD HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The PCD HAL driver can be used as follows: + + (#) Declare a PCD_HandleTypeDef handle structure, for example: + PCD_HandleTypeDef hpcd; + + (#) Fill parameters of Init structure in HCD handle + + (#) Call HAL_PCD_Init() API to initialize the PCD peripheral (Core, Device core, ...) + + (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API: + (##) Enable the PCD/USB Low Level interface clock using + (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) + + (##) Initialize the related GPIO clocks + (##) Configure PCD pin-out + (##) Configure PCD NVIC interrupt + + (#)Associate the Upper USB device stack to the HAL PCD Driver: + (##) hpcd.pData = pdev; + + (#)Enable PCD transmission and reception: + (##) HAL_PCD_Start(); + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PCD PCD + * @brief PCD HAL module driver + * @{ + */ + +#ifdef HAL_PCD_MODULE_ENABLED + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @defgroup PCD_Private_Macros PCD Private Macros + * @{ + */ +#define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b)) +#define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b)) +/** + * @} + */ + +/* Private functions prototypes ----------------------------------------------*/ +/** @defgroup PCD_Private_Functions PCD Private Functions + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum); +static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); +static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup PCD_Exported_Functions PCD Exported Functions + * @{ + */ + +/** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the PCD according to the specified + * parameters in the PCD_InitTypeDef and initialize the associated handle. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx; + uint8_t i; + + /* Check the PCD handle allocation */ + if (hpcd == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance)); + + USBx = hpcd->Instance; + + if (hpcd->State == HAL_PCD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hpcd->Lock = HAL_UNLOCKED; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SOFCallback = HAL_PCD_SOFCallback; + hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; + hpcd->ResetCallback = HAL_PCD_ResetCallback; + hpcd->SuspendCallback = HAL_PCD_SuspendCallback; + hpcd->ResumeCallback = HAL_PCD_ResumeCallback; + hpcd->ConnectCallback = HAL_PCD_ConnectCallback; + hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; + hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; + hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; + hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; + hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; + hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; + hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; + + if (hpcd->MspInitCallback == NULL) + { + hpcd->MspInitCallback = HAL_PCD_MspInit; + } + + /* Init the low level hardware */ + hpcd->MspInitCallback(hpcd); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + HAL_PCD_MspInit(hpcd); +#endif /* (USE_HAL_PCD_REGISTER_CALLBACKS) */ + } + + hpcd->State = HAL_PCD_STATE_BUSY; + + /* Disable DMA mode for FS instance */ + if ((USBx->CID & (0x1U << 8)) == 0U) + { + hpcd->Init.dma_enable = 0U; + } + + /* Disable the Interrupts */ + __HAL_PCD_DISABLE(hpcd); + + /*Init the Core (common init.) */ + if (USB_CoreInit(hpcd->Instance, hpcd->Init) != HAL_OK) + { + hpcd->State = HAL_PCD_STATE_ERROR; + return HAL_ERROR; + } + + /* Force Device Mode*/ + (void)USB_SetCurrentMode(hpcd->Instance, USB_DEVICE_MODE); + + /* Init endpoints structures */ + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + /* Init ep structure */ + hpcd->IN_ep[i].is_in = 1U; + hpcd->IN_ep[i].num = i; + hpcd->IN_ep[i].tx_fifo_num = i; + /* Control until ep is activated */ + hpcd->IN_ep[i].type = EP_TYPE_CTRL; + hpcd->IN_ep[i].maxpacket = 0U; + hpcd->IN_ep[i].xfer_buff = 0U; + hpcd->IN_ep[i].xfer_len = 0U; + } + + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + hpcd->OUT_ep[i].is_in = 0U; + hpcd->OUT_ep[i].num = i; + /* Control until ep is activated */ + hpcd->OUT_ep[i].type = EP_TYPE_CTRL; + hpcd->OUT_ep[i].maxpacket = 0U; + hpcd->OUT_ep[i].xfer_buff = 0U; + hpcd->OUT_ep[i].xfer_len = 0U; + } + + /* Init Device */ + if (USB_DevInit(hpcd->Instance, hpcd->Init) != HAL_OK) + { + hpcd->State = HAL_PCD_STATE_ERROR; + return HAL_ERROR; + } + + hpcd->USB_Address = 0U; + hpcd->State = HAL_PCD_STATE_READY; +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Activate LPM */ + if (hpcd->Init.lpm_enable == 1U) + { + (void)HAL_PCDEx_ActivateLPM(hpcd); + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + (void)USB_DevDisconnect(hpcd->Instance); + + return HAL_OK; +} + +/** + * @brief DeInitializes the PCD peripheral. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd) +{ + /* Check the PCD handle allocation */ + if (hpcd == NULL) + { + return HAL_ERROR; + } + + hpcd->State = HAL_PCD_STATE_BUSY; + + /* Stop Device */ + if (USB_StopDevice(hpcd->Instance) != HAL_OK) + { + return HAL_ERROR; + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + if (hpcd->MspDeInitCallback == NULL) + { + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hpcd->MspDeInitCallback(hpcd); +#else + /* DeInit the low level hardware: CLOCK, NVIC.*/ + HAL_PCD_MspDeInit(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + hpcd->State = HAL_PCD_STATE_RESET; + + return HAL_OK; +} + +/** + * @brief Initializes the PCD MSP. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes PCD MSP. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User USB PCD Callback + * To be used instead of the weak predefined callback + * @param hpcd USB PCD handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID + * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID + * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID + * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID + * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID + * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID + * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID + * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, + HAL_PCD_CallbackIDTypeDef CallbackID, + pPCD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_PCD_SOF_CB_ID : + hpcd->SOFCallback = pCallback; + break; + + case HAL_PCD_SETUPSTAGE_CB_ID : + hpcd->SetupStageCallback = pCallback; + break; + + case HAL_PCD_RESET_CB_ID : + hpcd->ResetCallback = pCallback; + break; + + case HAL_PCD_SUSPEND_CB_ID : + hpcd->SuspendCallback = pCallback; + break; + + case HAL_PCD_RESUME_CB_ID : + hpcd->ResumeCallback = pCallback; + break; + + case HAL_PCD_CONNECT_CB_ID : + hpcd->ConnectCallback = pCallback; + break; + + case HAL_PCD_DISCONNECT_CB_ID : + hpcd->DisconnectCallback = pCallback; + break; + + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = pCallback; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hpcd->State == HAL_PCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = pCallback; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + return status; +} + +/** + * @brief Unregister an USB PCD Callback + * USB PCD callback is redirected to the weak predefined callback + * @param hpcd USB PCD handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID + * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID + * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID + * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID + * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID + * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID + * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID + * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + /* Setup Legacy weak Callbacks */ + if (hpcd->State == HAL_PCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_PCD_SOF_CB_ID : + hpcd->SOFCallback = HAL_PCD_SOFCallback; + break; + + case HAL_PCD_SETUPSTAGE_CB_ID : + hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; + break; + + case HAL_PCD_RESET_CB_ID : + hpcd->ResetCallback = HAL_PCD_ResetCallback; + break; + + case HAL_PCD_SUSPEND_CB_ID : + hpcd->SuspendCallback = HAL_PCD_SuspendCallback; + break; + + case HAL_PCD_RESUME_CB_ID : + hpcd->ResumeCallback = HAL_PCD_ResumeCallback; + break; + + case HAL_PCD_CONNECT_CB_ID : + hpcd->ConnectCallback = HAL_PCD_ConnectCallback; + break; + + case HAL_PCD_DISCONNECT_CB_ID : + hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; + break; + + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = HAL_PCD_MspInit; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hpcd->State == HAL_PCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = HAL_PCD_MspInit; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + return status; +} + +/** + * @brief Register USB PCD Data OUT Stage Callback + * To be used instead of the weak HAL_PCD_DataOutStageCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Data OUT Stage Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataOutStageCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataOutStageCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Data OUT Stage Callback + * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataOutStageCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; /* Legacy weak DataOutStageCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Data IN Stage Callback + * To be used instead of the weak HAL_PCD_DataInStageCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Data IN Stage Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataInStageCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataInStageCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Data IN Stage Callback + * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataInStageCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; /* Legacy weak DataInStageCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Iso OUT incomplete Callback + * To be used instead of the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Iso OUT incomplete Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoOutIncpltCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOOUTIncompleteCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Iso OUT incomplete Callback + * USB PCD Iso OUT incomplete Callback is redirected + * to the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; /* Legacy weak ISOOUTIncompleteCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Iso IN incomplete Callback + * To be used instead of the weak HAL_PCD_ISOINIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Iso IN incomplete Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoInIncpltCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOINIncompleteCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Iso IN incomplete Callback + * USB PCD Iso IN incomplete Callback is redirected + * to the weak HAL_PCD_ISOINIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; /* Legacy weak ISOINIncompleteCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD BCD Callback + * To be used instead of the weak HAL_PCDEx_BCD_Callback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD BCD Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->BCDCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD BCD Callback + * USB BCD Callback is redirected to the weak HAL_PCDEx_BCD_Callback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; /* Legacy weak HAL_PCDEx_BCD_Callback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD LPM Callback + * To be used instead of the weak HAL_PCDEx_LPM_Callback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD LPM Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->LPMCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD LPM Callback + * USB LPM Callback is redirected to the weak HAL_PCDEx_LPM_Callback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; /* Legacy weak HAL_PCDEx_LPM_Callback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the PCD data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Start the USB device + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Enable USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + + __HAL_PCD_ENABLE(hpcd); + (void)USB_DevConnect(hpcd->Instance); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Stop the USB device. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + __HAL_PCD_DISABLE(hpcd); + (void)USB_DevDisconnect(hpcd->Instance); + + (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Disable USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Handles PCD interrupt request. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + USB_OTG_EPTypeDef *ep; + uint32_t i; + uint32_t ep_intr; + uint32_t epint; + uint32_t epnum; + uint32_t fifoemptymsk; + uint32_t RegVal; + + /* ensure that we are in device mode */ + if (USB_GetMode(hpcd->Instance) == USB_OTG_MODE_DEVICE) + { + /* avoid spurious interrupt */ + if (__HAL_PCD_IS_INVALID_INTERRUPT(hpcd)) + { + return; + } + + /* store current frame number */ + hpcd->FrameNumber = (USBx_DEVICE->DSTS & USB_OTG_DSTS_FNSOF_Msk) >> USB_OTG_DSTS_FNSOF_Pos; + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_MMIS)) + { + /* incorrect mode, acknowledge the interrupt */ + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_MMIS); + } + + /* Handle RxQLevel Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_RXFLVL)) + { + USB_MASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); + + RegVal = USBx->GRXSTSP; + + ep = &hpcd->OUT_ep[RegVal & USB_OTG_GRXSTSP_EPNUM]; + + if (((RegVal & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) + { + if ((RegVal & USB_OTG_GRXSTSP_BCNT) != 0U) + { + (void)USB_ReadPacket(USBx, ep->xfer_buff, + (uint16_t)((RegVal & USB_OTG_GRXSTSP_BCNT) >> 4)); + + ep->xfer_buff += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; + ep->xfer_count += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; + } + } + else if (((RegVal & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) + { + (void)USB_ReadPacket(USBx, (uint8_t *)hpcd->Setup, 8U); + ep->xfer_count += (RegVal & USB_OTG_GRXSTSP_BCNT) >> 4; + } + else + { + /* ... */ + } + + USB_UNMASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); + } + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OEPINT)) + { + epnum = 0U; + + /* Read in the device interrupt bits */ + ep_intr = USB_ReadDevAllOutEpInterrupt(hpcd->Instance); + + while (ep_intr != 0U) + { + if ((ep_intr & 0x1U) != 0U) + { + epint = USB_ReadDevOutEPInterrupt(hpcd->Instance, (uint8_t)epnum); + + if ((epint & USB_OTG_DOEPINT_XFRC) == USB_OTG_DOEPINT_XFRC) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_XFRC); + (void)PCD_EP_OutXfrComplete_int(hpcd, epnum); + } + + if ((epint & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STUP); + /* Class B setup phase done for previous decoded setup */ + (void)PCD_EP_OutSetupPacket_int(hpcd, epnum); + } + + if ((epint & USB_OTG_DOEPINT_OTEPDIS) == USB_OTG_DOEPINT_OTEPDIS) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPDIS); + } + + /* Clear OUT Endpoint disable interrupt */ + if ((epint & USB_OTG_DOEPINT_EPDISD) == USB_OTG_DOEPINT_EPDISD) + { + if ((USBx->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF) == USB_OTG_GINTSTS_BOUTNAKEFF) + { + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK; + } + + ep = &hpcd->OUT_ep[epnum]; + + if (ep->is_iso_incomplete == 1U) + { + ep->is_iso_incomplete = 0U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_EPDISD); + } + + /* Clear Status Phase Received interrupt */ + if ((epint & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + + /* Clear OUT NAK interrupt */ + if ((epint & USB_OTG_DOEPINT_NAK) == USB_OTG_DOEPINT_NAK) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_NAK); + } + } + epnum++; + ep_intr >>= 1U; + } + } + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IEPINT)) + { + /* Read in the device interrupt bits */ + ep_intr = USB_ReadDevAllInEpInterrupt(hpcd->Instance); + + epnum = 0U; + + while (ep_intr != 0U) + { + if ((ep_intr & 0x1U) != 0U) /* In ITR */ + { + epint = USB_ReadDevInEPInterrupt(hpcd->Instance, (uint8_t)epnum); + + if ((epint & USB_OTG_DIEPINT_XFRC) == USB_OTG_DIEPINT_XFRC) + { + fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); + USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; + + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_XFRC); + + if (hpcd->Init.dma_enable == 1U) + { + hpcd->IN_ep[epnum].xfer_buff += hpcd->IN_ep[epnum].maxpacket; + + /* this is ZLP, so prepare EP0 for next setup */ + if ((epnum == 0U) && (hpcd->IN_ep[epnum].xfer_len == 0U)) + { + /* prepare to rx more setup packets */ + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataInStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataInStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + if ((epint & USB_OTG_DIEPINT_TOC) == USB_OTG_DIEPINT_TOC) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_TOC); + } + if ((epint & USB_OTG_DIEPINT_ITTXFE) == USB_OTG_DIEPINT_ITTXFE) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_ITTXFE); + } + if ((epint & USB_OTG_DIEPINT_INEPNE) == USB_OTG_DIEPINT_INEPNE) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_INEPNE); + } + if ((epint & USB_OTG_DIEPINT_EPDISD) == USB_OTG_DIEPINT_EPDISD) + { + (void)USB_FlushTxFifo(USBx, epnum); + + ep = &hpcd->IN_ep[epnum]; + + if (ep->is_iso_incomplete == 1U) + { + ep->is_iso_incomplete = 0U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ISOINIncompleteCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_ISOINIncompleteCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_EPDISD); + } + if ((epint & USB_OTG_DIEPINT_TXFE) == USB_OTG_DIEPINT_TXFE) + { + (void)PCD_WriteEmptyTxFifo(hpcd, epnum); + } + } + epnum++; + ep_intr >>= 1U; + } + } + + /* Handle Resume Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT)) + { + /* Clear the Remote Wake-up Signaling */ + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; + + if (hpcd->LPM_State == LPM_L1) + { + hpcd->LPM_State = LPM_L0; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->LPMCallback(hpcd, PCD_LPM_L0_ACTIVE); +#else + HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L0_ACTIVE); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ResumeCallback(hpcd); +#else + HAL_PCD_ResumeCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT); + } + + /* Handle Suspend Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP)) + { + if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SuspendCallback(hpcd); +#else + HAL_PCD_SuspendCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP); + } +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Handle LPM Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT)) + { + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT); + + if (hpcd->LPM_State == LPM_L0) + { + hpcd->LPM_State = LPM_L1; + hpcd->BESL = (hpcd->Instance->GLPMCFG & USB_OTG_GLPMCFG_BESL) >> 2U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->LPMCallback(hpcd, PCD_LPM_L1_ACTIVE); +#else + HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L1_ACTIVE); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SuspendCallback(hpcd); +#else + HAL_PCD_SuspendCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + /* Handle Reset Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBRST)) + { + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; + (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); + + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + USBx_INEP(i)->DIEPINT = 0xFB7FU; + USBx_INEP(i)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + USBx_OUTEP(i)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + USBx_OUTEP(i)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + } + USBx_DEVICE->DAINTMSK |= 0x10001U; + + if (hpcd->Init.use_dedicated_ep1 != 0U) + { + USBx_DEVICE->DOUTEP1MSK |= USB_OTG_DOEPMSK_STUPM | + USB_OTG_DOEPMSK_XFRCM | + USB_OTG_DOEPMSK_EPDM; + + USBx_DEVICE->DINEP1MSK |= USB_OTG_DIEPMSK_TOM | + USB_OTG_DIEPMSK_XFRCM | + USB_OTG_DIEPMSK_EPDM; + } + else + { + USBx_DEVICE->DOEPMSK |= USB_OTG_DOEPMSK_STUPM | + USB_OTG_DOEPMSK_XFRCM | + USB_OTG_DOEPMSK_EPDM | + USB_OTG_DOEPMSK_OTEPSPRM | + USB_OTG_DOEPMSK_NAKM; + + USBx_DEVICE->DIEPMSK |= USB_OTG_DIEPMSK_TOM | + USB_OTG_DIEPMSK_XFRCM | + USB_OTG_DIEPMSK_EPDM; + } + + /* Set Default Address to 0 */ + USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; + + /* setup EP0 to receive SETUP packets */ + (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, + (uint8_t *)hpcd->Setup); + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBRST); + } + + /* Handle Enumeration done Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE)) + { + (void)USB_ActivateSetup(hpcd->Instance); + hpcd->Init.speed = USB_GetDevSpeed(hpcd->Instance); + + /* Set USB Turnaround time */ + (void)USB_SetTurnaroundTime(hpcd->Instance, + HAL_RCC_GetHCLKFreq(), + (uint8_t)hpcd->Init.speed); + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ResetCallback(hpcd); +#else + HAL_PCD_ResetCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE); + } + + /* Handle SOF Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SOF)) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SOFCallback(hpcd); +#else + HAL_PCD_SOFCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SOF); + } + + /* Handle Global OUT NAK effective Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_BOUTNAKEFF)) + { + USBx->GINTMSK &= ~USB_OTG_GINTMSK_GONAKEFFM; + + for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) + { + if (hpcd->OUT_ep[epnum].is_iso_incomplete == 1U) + { + /* Abort current transaction and disable the EP */ + (void)HAL_PCD_EP_Abort(hpcd, (uint8_t)epnum); + } + } + } + + /* Handle Incomplete ISO IN Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR)) + { + for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) + { + RegVal = USBx_INEP(epnum)->DIEPCTL; + + if ((hpcd->IN_ep[epnum].type == EP_TYPE_ISOC) && + ((RegVal & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA)) + { + hpcd->IN_ep[epnum].is_iso_incomplete = 1U; + + /* Abort current transaction and disable the EP */ + (void)HAL_PCD_EP_Abort(hpcd, (uint8_t)(epnum | 0x80U)); + } + } + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR); + } + + /* Handle Incomplete ISO OUT Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) + { + for (epnum = 1U; epnum < hpcd->Init.dev_endpoints; epnum++) + { + RegVal = USBx_OUTEP(epnum)->DOEPCTL; + + if ((hpcd->OUT_ep[epnum].type == EP_TYPE_ISOC) && + ((RegVal & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) && + ((RegVal & (0x1U << 16)) == (hpcd->FrameNumber & 0x1U))) + { + hpcd->OUT_ep[epnum].is_iso_incomplete = 1U; + + USBx->GINTMSK |= USB_OTG_GINTMSK_GONAKEFFM; + + if ((USBx->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF) == 0U) + { + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SGONAK; + break; + } + } + } + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); + } + + /* Handle Connection event Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT)) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ConnectCallback(hpcd); +#else + HAL_PCD_ConnectCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT); + } + + /* Handle Disconnection event Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OTGINT)) + { + RegVal = hpcd->Instance->GOTGINT; + + if ((RegVal & USB_OTG_GOTGINT_SEDET) == USB_OTG_GOTGINT_SEDET) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DisconnectCallback(hpcd); +#else + HAL_PCD_DisconnectCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + hpcd->Instance->GOTGINT |= RegVal; + } + } +} + + +/** + * @brief Handles PCD Wakeup interrupt request. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx; + + USBx = hpcd->Instance; + + if ((USBx->CID & (0x1U << 8)) == 0U) + { + /* Clear EXTI pending Bit */ + __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG(); + } + else + { + /* Clear EXTI pending Bit */ + __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG(); + } +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @brief Data OUT stage callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DataOutStageCallback could be implemented in the user file + */ +} + +/** + * @brief Data IN stage callback + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DataInStageCallback could be implemented in the user file + */ +} +/** + * @brief Setup stage callback + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SetupStageCallback could be implemented in the user file + */ +} + +/** + * @brief USB Start Of Frame callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SOFCallback could be implemented in the user file + */ +} + +/** + * @brief USB Reset callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ResetCallback could be implemented in the user file + */ +} + +/** + * @brief Suspend event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SuspendCallback could be implemented in the user file + */ +} + +/** + * @brief Resume event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ResumeCallback could be implemented in the user file + */ +} + +/** + * @brief Incomplete ISO OUT callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file + */ +} + +/** + * @brief Incomplete ISO IN callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file + */ +} + +/** + * @brief Connection event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ConnectCallback could be implemented in the user file + */ +} + +/** + * @brief Disconnection event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DisconnectCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the PCD data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Connect the USB device + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Enable USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + (void)USB_DevConnect(hpcd->Instance); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Disconnect the USB device. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + (void)USB_DevDisconnect(hpcd->Instance); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Disable USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Set the USB Device address. + * @param hpcd PCD handle + * @param address new device address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address) +{ + __HAL_LOCK(hpcd); + hpcd->USB_Address = address; + (void)USB_SetDevAddress(hpcd->Instance, address); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} +/** + * @brief Open and configure an endpoint. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param ep_mps endpoint max packet size + * @param ep_type endpoint type + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, + uint16_t ep_mps, uint8_t ep_type) +{ + HAL_StatusTypeDef ret = HAL_OK; + PCD_EPTypeDef *ep; + + if ((ep_addr & 0x80U) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + + ep->num = ep_addr & EP_ADDR_MSK; + ep->maxpacket = ep_mps; + ep->type = ep_type; + + if (ep->is_in != 0U) + { + /* Assign a Tx FIFO */ + ep->tx_fifo_num = ep->num; + } + /* Set initial data PID. */ + if (ep_type == EP_TYPE_BULK) + { + ep->data_pid_start = 0U; + } + + __HAL_LOCK(hpcd); + (void)USB_ActivateEndpoint(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + + return ret; +} + +/** + * @brief Deactivate an endpoint. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if ((ep_addr & 0x80U) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + (void)USB_DeactivateEndpoint(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + return HAL_OK; +} + + +/** + * @brief Receive an amount of data. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param pBuf pointer to the reception buffer + * @param len amount of data to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) +{ + PCD_EPTypeDef *ep; + + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + + /*setup and start the Xfer */ + ep->xfer_buff = pBuf; + ep->xfer_len = len; + ep->xfer_count = 0U; + ep->is_in = 0U; + ep->num = ep_addr & EP_ADDR_MSK; + + if (hpcd->Init.dma_enable == 1U) + { + ep->dma_addr = (uint32_t)pBuf; + } + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + else + { + (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + + return HAL_OK; +} + +/** + * @brief Get Received Data Size + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval Data Size + */ +uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + return hpcd->OUT_ep[ep_addr & EP_ADDR_MSK].xfer_count; +} +/** + * @brief Send an amount of data + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param pBuf pointer to the transmission buffer + * @param len amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) +{ + PCD_EPTypeDef *ep; + + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + + /*setup and start the Xfer */ + ep->xfer_buff = pBuf; + ep->xfer_len = len; + ep->xfer_count = 0U; + ep->is_in = 1U; + ep->num = ep_addr & EP_ADDR_MSK; + + if (hpcd->Init.dma_enable == 1U) + { + ep->dma_addr = (uint32_t)pBuf; + } + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + else + { + (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + + return HAL_OK; +} + +/** + * @brief Set a STALL condition over an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if (((uint32_t)ep_addr & EP_ADDR_MSK) > hpcd->Init.dev_endpoints) + { + return HAL_ERROR; + } + + if ((0x80U & ep_addr) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr]; + ep->is_in = 0U; + } + + ep->is_stall = 1U; + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + + (void)USB_EPSetStall(hpcd->Instance, ep); + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Clear a STALL condition over in an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if (((uint32_t)ep_addr & 0x0FU) > hpcd->Init.dev_endpoints) + { + return HAL_ERROR; + } + + if ((0x80U & ep_addr) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + + ep->is_stall = 0U; + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + (void)USB_EPClearStall(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Abort an USB EP transaction. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Abort(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + HAL_StatusTypeDef ret; + PCD_EPTypeDef *ep; + + if ((0x80U & ep_addr) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + } + + /* Stop Xfer */ + ret = USB_EPStopXfer(hpcd->Instance, ep); + + return ret; +} + +/** + * @brief Flush an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + __HAL_LOCK(hpcd); + + if ((ep_addr & 0x80U) == 0x80U) + { + (void)USB_FlushTxFifo(hpcd->Instance, (uint32_t)ep_addr & EP_ADDR_MSK); + } + else + { + (void)USB_FlushRxFifo(hpcd->Instance); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Activate remote wakeup signalling + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) +{ + return (USB_ActivateRemoteWakeup(hpcd->Instance)); +} + +/** + * @brief De-activate remote wakeup signalling. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) +{ + return (USB_DeActivateRemoteWakeup(hpcd->Instance)); +} + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the PCD handle state. + * @param hpcd PCD handle + * @retval HAL state + */ +PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd) +{ + return hpcd->State; +} + +/** + * @brief Set the USB Device high speed test mode. + * @param hpcd PCD handle + * @param testmode USB Device high speed test mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_SetTestMode(PCD_HandleTypeDef *hpcd, uint8_t testmode) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + + switch (testmode) + { + case TEST_J: + case TEST_K: + case TEST_SE0_NAK: + case TEST_PACKET: + case TEST_FORCE_EN: + USBx_DEVICE->DCTL |= (uint32_t)testmode << 4; + break; + + default: + break; + } + + return HAL_OK; +} +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup PCD_Private_Functions + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Check FIFO for the next packet to be loaded. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + USB_OTG_EPTypeDef *ep; + uint32_t len; + uint32_t len32b; + uint32_t fifoemptymsk; + + ep = &hpcd->IN_ep[epnum]; + + if (ep->xfer_count > ep->xfer_len) + { + return HAL_ERROR; + } + + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + + len32b = (len + 3U) / 4U; + + while (((USBx_INEP(epnum)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= len32b) && + (ep->xfer_count < ep->xfer_len) && (ep->xfer_len != 0U)) + { + /* Write the FIFO */ + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + len32b = (len + 3U) / 4U; + + (void)USB_WritePacket(USBx, ep->xfer_buff, (uint8_t)epnum, (uint16_t)len, + (uint8_t)hpcd->Init.dma_enable); + + ep->xfer_buff += len; + ep->xfer_count += len; + } + + if (ep->xfer_len <= ep->xfer_count) + { + fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); + USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; + } + + return HAL_OK; +} + + +/** + * @brief process EP OUT transfer complete interrupt. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_EPTypeDef *ep; + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; + + if (hpcd->Init.dma_enable == 1U) + { + if ((DoepintReg & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) /* Class C */ + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + } + else if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) /* Class E */ + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + else if ((DoepintReg & (USB_OTG_DOEPINT_STUP | USB_OTG_DOEPINT_OTEPSPR)) == 0U) + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + else + { + ep = &hpcd->OUT_ep[epnum]; + + /* out data packet received over EP */ + ep->xfer_count = ep->xfer_size - (USBx_OUTEP(epnum)->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ); + + if (epnum == 0U) + { + if (ep->xfer_len == 0U) + { + /* this is ZLP, so prepare EP0 for next setup */ + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } + else + { + ep->xfer_buff += ep->xfer_count; + } + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + else + { + /* ... */ + } + } + else + { + if (gSNPSiD == USB_OTG_CORE_ID_310A) + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + else + { + if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + else + { + if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) + { + /* this is ZLP, so prepare EP0 for next setup */ + (void)USB_EP0_OutStart(hpcd->Instance, 0U, (uint8_t *)hpcd->Setup); + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + + return HAL_OK; +} + + +/** + * @brief process EP OUT setup packet received interrupt. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; + + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + + /* Inform the upper layer that a setup packet is available */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SetupStageCallback(hpcd); +#else + HAL_PCD_SetupStageCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && (hpcd->Init.dma_enable == 1U)) + { + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } + + return HAL_OK; +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* HAL_PCD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c index 292faf1..07fcf73 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c @@ -1,341 +1,341 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd_ex.c - * @author MCD Application Team - * @brief PCD Extended HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Extended features functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PCDEx PCDEx - * @brief PCD Extended HAL module driver - * @{ - */ - -#ifdef HAL_PCD_MODULE_ENABLED - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup PCDEx_Exported_Functions PCDEx Exported Functions - * @{ - */ - -/** @defgroup PCDEx_Exported_Functions_Group1 Peripheral Control functions - * @brief PCDEx control functions - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Update FIFO configuration - -@endverbatim - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Set Tx FIFO - * @param hpcd PCD handle - * @param fifo The number of Tx fifo - * @param size Fifo size - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size) -{ - uint8_t i; - uint32_t Tx_Offset; - - /* TXn min size = 16 words. (n : Transmit FIFO index) - When a TxFIFO is not used, the Configuration should be as follows: - case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) - --> Txm can use the space allocated for Txn. - case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) - --> Txn should be configured with the minimum space of 16 words - The FIFO is used optimally when used TxFIFOs are allocated in the top - of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. - When DMA is used 3n * FIFO locations should be reserved for internal DMA registers */ - - Tx_Offset = hpcd->Instance->GRXFSIZ; - - if (fifo == 0U) - { - hpcd->Instance->DIEPTXF0_HNPTXFSIZ = ((uint32_t)size << 16) | Tx_Offset; - } - else - { - Tx_Offset += (hpcd->Instance->DIEPTXF0_HNPTXFSIZ) >> 16; - for (i = 0U; i < (fifo - 1U); i++) - { - Tx_Offset += (hpcd->Instance->DIEPTXF[i] >> 16); - } - - /* Multiply Tx_Size by 2 to get higher performance */ - hpcd->Instance->DIEPTXF[fifo - 1U] = ((uint32_t)size << 16) | Tx_Offset; - } - - return HAL_OK; -} - -/** - * @brief Set Rx FIFO - * @param hpcd PCD handle - * @param size Size of Rx fifo - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size) -{ - hpcd->Instance->GRXFSIZ = size; - - return HAL_OK; -} -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Activate LPM feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - hpcd->lpm_active = 1U; - hpcd->LPM_State = LPM_L0; - USBx->GINTMSK |= USB_OTG_GINTMSK_LPMINTM; - USBx->GLPMCFG |= (USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); - - return HAL_OK; -} - -/** - * @brief Deactivate LPM feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - hpcd->lpm_active = 0U; - USBx->GINTMSK &= ~USB_OTG_GINTMSK_LPMINTM; - USBx->GLPMCFG &= ~(USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); - - return HAL_OK; -} -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Handle BatteryCharging Process. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t tickstart = HAL_GetTick(); - - /* Enable DCD : Data Contact Detect */ - USBx->GCCFG |= USB_OTG_GCCFG_DCDEN; - - /* Wait for Min DCD Timeout */ - HAL_Delay(300U); - - /* Check Detect flag */ - if ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == USB_OTG_GCCFG_DCDET) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_CONTACT_DETECTION); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CONTACT_DETECTION); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - /* Primary detection: checks if connected to Standard Downstream Port - (without charging capability) */ - USBx->GCCFG &= ~ USB_OTG_GCCFG_DCDEN; - HAL_Delay(50U); - USBx->GCCFG |= USB_OTG_GCCFG_PDEN; - HAL_Delay(50U); - - if ((USBx->GCCFG & USB_OTG_GCCFG_PDET) == 0U) - { - /* Case of Standard Downstream Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { - /* start secondary detection to check connection to Charging Downstream - Port or Dedicated Charging Port */ - USBx->GCCFG &= ~ USB_OTG_GCCFG_PDEN; - HAL_Delay(50U); - USBx->GCCFG |= USB_OTG_GCCFG_SDEN; - HAL_Delay(50U); - - if ((USBx->GCCFG & USB_OTG_GCCFG_SDET) == USB_OTG_GCCFG_SDET) - { - /* case Dedicated Charging Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { - /* case Charging Downstream Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - - /* Battery Charging capability discovery finished */ - (void)HAL_PCDEx_DeActivateBCD(hpcd); - - /* Check for the Timeout, else start USB Device */ - if ((HAL_GetTick() - tickstart) > 1000U) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_ERROR); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_ERROR); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Activate BatteryCharging feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); - USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); - - /* Power Down USB transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - - /* Enable Battery charging */ - USBx->GCCFG |= USB_OTG_GCCFG_BCDEN; - - hpcd->battery_charging_active = 1U; - - return HAL_OK; -} - -/** - * @brief Deactivate BatteryCharging feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); - USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); - - /* Disable Battery charging */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); - - hpcd->battery_charging_active = 0U; - - return HAL_OK; -} -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @brief Send LPM message to user layer callback. - * @param hpcd PCD handle - * @param msg LPM message - * @retval HAL status - */ -__weak void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(msg); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCDEx_LPM_Callback could be implemented in the user file - */ -} - -/** - * @brief Send BatteryCharging message to user layer callback. - * @param hpcd PCD handle - * @param msg LPM message - * @retval HAL status - */ -__weak void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(msg); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCDEx_BCD_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* HAL_PCD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd_ex.c + * @author MCD Application Team + * @brief PCD Extended HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Extended features functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PCDEx PCDEx + * @brief PCD Extended HAL module driver + * @{ + */ + +#ifdef HAL_PCD_MODULE_ENABLED + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup PCDEx_Exported_Functions PCDEx Exported Functions + * @{ + */ + +/** @defgroup PCDEx_Exported_Functions_Group1 Peripheral Control functions + * @brief PCDEx control functions + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Update FIFO configuration + +@endverbatim + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Set Tx FIFO + * @param hpcd PCD handle + * @param fifo The number of Tx fifo + * @param size Fifo size + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size) +{ + uint8_t i; + uint32_t Tx_Offset; + + /* TXn min size = 16 words. (n : Transmit FIFO index) + When a TxFIFO is not used, the Configuration should be as follows: + case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) + --> Txm can use the space allocated for Txn. + case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) + --> Txn should be configured with the minimum space of 16 words + The FIFO is used optimally when used TxFIFOs are allocated in the top + of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. + When DMA is used 3n * FIFO locations should be reserved for internal DMA registers */ + + Tx_Offset = hpcd->Instance->GRXFSIZ; + + if (fifo == 0U) + { + hpcd->Instance->DIEPTXF0_HNPTXFSIZ = ((uint32_t)size << 16) | Tx_Offset; + } + else + { + Tx_Offset += (hpcd->Instance->DIEPTXF0_HNPTXFSIZ) >> 16; + for (i = 0U; i < (fifo - 1U); i++) + { + Tx_Offset += (hpcd->Instance->DIEPTXF[i] >> 16); + } + + /* Multiply Tx_Size by 2 to get higher performance */ + hpcd->Instance->DIEPTXF[fifo - 1U] = ((uint32_t)size << 16) | Tx_Offset; + } + + return HAL_OK; +} + +/** + * @brief Set Rx FIFO + * @param hpcd PCD handle + * @param size Size of Rx fifo + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size) +{ + hpcd->Instance->GRXFSIZ = size; + + return HAL_OK; +} +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Activate LPM feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + hpcd->lpm_active = 1U; + hpcd->LPM_State = LPM_L0; + USBx->GINTMSK |= USB_OTG_GINTMSK_LPMINTM; + USBx->GLPMCFG |= (USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); + + return HAL_OK; +} + +/** + * @brief Deactivate LPM feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + hpcd->lpm_active = 0U; + USBx->GINTMSK &= ~USB_OTG_GINTMSK_LPMINTM; + USBx->GLPMCFG &= ~(USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); + + return HAL_OK; +} +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Handle BatteryCharging Process. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t tickstart = HAL_GetTick(); + + /* Enable DCD : Data Contact Detect */ + USBx->GCCFG |= USB_OTG_GCCFG_DCDEN; + + /* Wait for Min DCD Timeout */ + HAL_Delay(300U); + + /* Check Detect flag */ + if ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == USB_OTG_GCCFG_DCDET) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_CONTACT_DETECTION); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CONTACT_DETECTION); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + /* Primary detection: checks if connected to Standard Downstream Port + (without charging capability) */ + USBx->GCCFG &= ~ USB_OTG_GCCFG_DCDEN; + HAL_Delay(50U); + USBx->GCCFG |= USB_OTG_GCCFG_PDEN; + HAL_Delay(50U); + + if ((USBx->GCCFG & USB_OTG_GCCFG_PDET) == 0U) + { + /* Case of Standard Downstream Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { + /* start secondary detection to check connection to Charging Downstream + Port or Dedicated Charging Port */ + USBx->GCCFG &= ~ USB_OTG_GCCFG_PDEN; + HAL_Delay(50U); + USBx->GCCFG |= USB_OTG_GCCFG_SDEN; + HAL_Delay(50U); + + if ((USBx->GCCFG & USB_OTG_GCCFG_SDET) == USB_OTG_GCCFG_SDET) + { + /* case Dedicated Charging Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { + /* case Charging Downstream Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + + /* Battery Charging capability discovery finished */ + (void)HAL_PCDEx_DeActivateBCD(hpcd); + + /* Check for the Timeout, else start USB Device */ + if ((HAL_GetTick() - tickstart) > 1000U) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_ERROR); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_ERROR); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Activate BatteryCharging feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); + USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); + + /* Power Down USB transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + + /* Enable Battery charging */ + USBx->GCCFG |= USB_OTG_GCCFG_BCDEN; + + hpcd->battery_charging_active = 1U; + + return HAL_OK; +} + +/** + * @brief Deactivate BatteryCharging feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); + USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); + + /* Disable Battery charging */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); + + hpcd->battery_charging_active = 0U; + + return HAL_OK; +} +#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +/** + * @brief Send LPM message to user layer callback. + * @param hpcd PCD handle + * @param msg LPM message + * @retval HAL status + */ +__weak void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(msg); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCDEx_LPM_Callback could be implemented in the user file + */ +} + +/** + * @brief Send BatteryCharging message to user layer callback. + * @param hpcd PCD handle + * @param msg LPM message + * @retval HAL status + */ +__weak void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(msg); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCDEx_BCD_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* HAL_PCD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c index b4bb483..bf60fc0 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c @@ -1,571 +1,571 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr.c - * @author MCD Application Team - * @brief PWR HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Power Controller (PWR) peripheral: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PWR PWR - * @brief PWR HAL module driver - * @{ - */ - -#ifdef HAL_PWR_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup PWR_Private_Constants - * @{ - */ - -/** @defgroup PWR_PVD_Mode_Mask PWR PVD Mode Mask - * @{ - */ -#define PVD_MODE_IT 0x00010000U -#define PVD_MODE_EVT 0x00020000U -#define PVD_RISING_EDGE 0x00000001U -#define PVD_FALLING_EDGE 0x00000002U -/** - * @} - */ - -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup PWR_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @defgroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and de-initialization functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - After reset, the backup domain (RTC registers, RTC backup data - registers and backup SRAM) is protected against possible unwanted - write accesses. - To enable access to the RTC Domain and RTC registers, proceed as follows: - (+) Enable the Power Controller (PWR) APB1 interface clock using the - __HAL_RCC_PWR_CLK_ENABLE() macro. - (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. - -@endverbatim - * @{ - */ - -/** - * @brief Deinitializes the HAL PWR peripheral registers to their default reset values. - * @retval None - */ -void HAL_PWR_DeInit(void) -{ - __HAL_RCC_PWR_FORCE_RESET(); - __HAL_RCC_PWR_RELEASE_RESET(); -} - -/** - * @brief Enables access to the backup domain (RTC registers, RTC - * backup data registers and backup SRAM). - * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the - * Backup Domain Access should be kept enabled. - * @note The following sequence is required to bypass the delay between - * DBP bit programming and the effective enabling of the backup domain. - * Please check the Errata Sheet for more details under "Possible delay - * in backup domain protection disabling/enabling after programming the - * DBP bit" section. - * @retval None - */ -void HAL_PWR_EnableBkUpAccess(void) -{ - __IO uint32_t dummyread; - *(__IO uint32_t *) CR_DBP_BB = (uint32_t)ENABLE; - dummyread = PWR->CR; - UNUSED(dummyread); -} - -/** - * @brief Disables access to the backup domain (RTC registers, RTC - * backup data registers and backup SRAM). - * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the - * Backup Domain Access should be kept enabled. - * @note The following sequence is required to bypass the delay between - * DBP bit programming and the effective disabling of the backup domain. - * Please check the Errata Sheet for more details under "Possible delay - * in backup domain protection disabling/enabling after programming the - * DBP bit" section. - * @retval None - */ -void HAL_PWR_DisableBkUpAccess(void) -{ - __IO uint32_t dummyread; - *(__IO uint32_t *) CR_DBP_BB = (uint32_t)DISABLE; - dummyread = PWR->CR; - UNUSED(dummyread); -} - -/** - * @} - */ - -/** @defgroup PWR_Exported_Functions_Group2 Peripheral Control functions - * @brief Low Power modes configuration functions - * -@verbatim - - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - - *** PVD configuration *** - ========================= - [..] - (+) The PVD is used to monitor the VDD power supply by comparing it to a - threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR). - (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower - than the PVD threshold. This event is internally connected to the EXTI - line16 and can generate an interrupt if enabled. This is done through - __HAL_PWR_PVD_EXTI_ENABLE_IT() macro. - (+) The PVD is stopped in Standby mode. - - *** Wake-up pin configuration *** - ================================ - [..] - (+) Wake-up pin is used to wake up the system from Standby mode. This pin is - forced in input pull-down configuration and is active on rising edges. - (+) There is one Wake-up pin: Wake-up Pin 1 on PA.00. - (++) For STM32F446xx there are two Wake-Up pins: Pin1 on PA.00 and Pin2 on PC.13 - (++) For STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx there are three Wake-Up pins: Pin1 on PA.00, Pin2 on PC.00 and Pin3 on PC.01 - - *** Low Power modes configuration *** - ===================================== - [..] - The devices feature 3 low-power modes: - (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running. - (+) Stop mode: all clocks are stopped, regulator running, regulator - in low power mode - (+) Standby mode: 1.2V domain powered off. - - *** Sleep mode *** - ================== - [..] - (+) Entry: - The Sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI) - functions with - (++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction - (++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction - - -@@- The Regulator parameter is not used for the STM32F4 family - and is kept as parameter just to maintain compatibility with the - lower power families (STM32L). - (+) Exit: - Any peripheral interrupt acknowledged by the nested vectored interrupt - controller (NVIC) can wake up the device from Sleep mode. - - *** Stop mode *** - ================= - [..] - In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI, - and the HSE RC oscillators are disabled. Internal SRAM and register contents - are preserved. - The voltage regulator can be configured either in normal or low-power mode. - To minimize the consumption In Stop mode, FLASH can be powered off before - entering the Stop mode using the HAL_PWREx_EnableFlashPowerDown() function. - It can be switched on again by software after exiting the Stop mode using - the HAL_PWREx_DisableFlashPowerDown() function. - - (+) Entry: - The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON) - function with: - (++) Main regulator ON. - (++) Low Power regulator ON. - (+) Exit: - Any EXTI Line (Internal or External) configured in Interrupt/Event mode. - - *** Standby mode *** - ==================== - [..] - (+) - The Standby mode allows to achieve the lowest power consumption. It is based - on the Cortex-M4 deep sleep mode, with the voltage regulator disabled. - The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and - the HSE oscillator are also switched off. SRAM and register contents are lost - except for the RTC registers, RTC backup registers, backup SRAM and Standby - circuitry. - - The voltage regulator is OFF. - - (++) Entry: - (+++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function. - (++) Exit: - (+++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wake-up, - tamper event, time-stamp event, external reset in NRST pin, IWDG reset. - - *** Auto-wake-up (AWU) from low-power mode *** - ============================================= - [..] - - (+) The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC - Wake-up event, a tamper event or a time-stamp event, without depending on - an external interrupt (Auto-wake-up mode). - - (+) RTC auto-wake-up (AWU) from the Stop and Standby modes - - (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to - configure the RTC to generate the RTC alarm using the HAL_RTC_SetAlarm_IT() function. - - (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it - is necessary to configure the RTC to detect the tamper or time stamp event using the - HAL_RTCEx_SetTimeStamp_IT() or HAL_RTCEx_SetTamper_IT() functions. - - (++) To wake up from the Stop mode with an RTC Wake-up event, it is necessary to - configure the RTC to generate the RTC Wake-up event using the HAL_RTCEx_SetWakeUpTimer_IT() function. - -@endverbatim - * @{ - */ - -/** - * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). - * @param sConfigPVD pointer to an PWR_PVDTypeDef structure that contains the configuration - * information for the PVD. - * @note Refer to the electrical characteristics of your device datasheet for - * more details about the voltage threshold corresponding to each - * detection level. - * @retval None - */ -void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD) -{ - /* Check the parameters */ - assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel)); - assert_param(IS_PWR_PVD_MODE(sConfigPVD->Mode)); - - /* Set PLS[7:5] bits according to PVDLevel value */ - MODIFY_REG(PWR->CR, PWR_CR_PLS, sConfigPVD->PVDLevel); - - /* Clear any previous config. Keep it clear if no event or IT mode is selected */ - __HAL_PWR_PVD_EXTI_DISABLE_EVENT(); - __HAL_PWR_PVD_EXTI_DISABLE_IT(); - __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE(); - __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); - - /* Configure interrupt mode */ - if((sConfigPVD->Mode & PVD_MODE_IT) == PVD_MODE_IT) - { - __HAL_PWR_PVD_EXTI_ENABLE_IT(); - } - - /* Configure event mode */ - if((sConfigPVD->Mode & PVD_MODE_EVT) == PVD_MODE_EVT) - { - __HAL_PWR_PVD_EXTI_ENABLE_EVENT(); - } - - /* Configure the edge */ - if((sConfigPVD->Mode & PVD_RISING_EDGE) == PVD_RISING_EDGE) - { - __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE(); - } - - if((sConfigPVD->Mode & PVD_FALLING_EDGE) == PVD_FALLING_EDGE) - { - __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE(); - } -} - -/** - * @brief Enables the Power Voltage Detector(PVD). - * @retval None - */ -void HAL_PWR_EnablePVD(void) -{ - *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Power Voltage Detector(PVD). - * @retval None - */ -void HAL_PWR_DisablePVD(void) -{ - *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)DISABLE; -} - -/** - * @brief Enables the Wake-up PINx functionality. - * @param WakeUpPinx Specifies the Power Wake-Up pin to enable. - * This parameter can be one of the following values: - * @arg PWR_WAKEUP_PIN1 - * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @retval None - */ -void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx) -{ - /* Check the parameter */ - assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); - - /* Enable the wake up pin */ - SET_BIT(PWR->CSR, WakeUpPinx); -} - -/** - * @brief Disables the Wake-up PINx functionality. - * @param WakeUpPinx Specifies the Power Wake-Up pin to disable. - * This parameter can be one of the following values: - * @arg PWR_WAKEUP_PIN1 - * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @retval None - */ -void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx) -{ - /* Check the parameter */ - assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); - - /* Disable the wake up pin */ - CLEAR_BIT(PWR->CSR, WakeUpPinx); -} - -/** - * @brief Enters Sleep mode. - * - * @note In Sleep mode, all I/O pins keep the same state as in Run mode. - * - * @note In Sleep mode, the systick is stopped to avoid exit from this mode with - * systick interrupt when used as time base for Timeout - * - * @param Regulator Specifies the regulator state in SLEEP mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_ON: SLEEP mode with regulator ON - * @arg PWR_LOWPOWERREGULATOR_ON: SLEEP mode with low power regulator ON - * @note This parameter is not used for the STM32F4 family and is kept as parameter - * just to maintain compatibility with the lower power families. - * @param SLEEPEntry Specifies if SLEEP mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction - * @arg PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction - * @retval None - */ -void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry) -{ - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR(Regulator)); - assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); - - /* Clear SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* Select SLEEP mode entry -------------------------------------------------*/ - if(SLEEPEntry == PWR_SLEEPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __SEV(); - __WFE(); - __WFE(); - } -} - -/** - * @brief Enters Stop mode. - * @note In Stop mode, all I/O pins keep the same state as in Run mode. - * @note When exiting Stop mode by issuing an interrupt or a wake-up event, - * the HSI RC oscillator is selected as system clock. - * @note When the voltage regulator operates in low power mode, an additional - * startup delay is incurred when waking up from Stop mode. - * By keeping the internal regulator ON during Stop mode, the consumption - * is higher although the startup time is reduced. - * @param Regulator Specifies the regulator state in Stop mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_ON: Stop mode with regulator ON - * @arg PWR_LOWPOWERREGULATOR_ON: Stop mode with low power regulator ON - * @param STOPEntry Specifies if Stop mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_STOPENTRY_WFI: Enter Stop mode with WFI instruction - * @arg PWR_STOPENTRY_WFE: Enter Stop mode with WFE instruction - * @retval None - */ -void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry) -{ - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR(Regulator)); - assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); - - /* Select the regulator state in Stop mode: Set PDDS and LPDS bits according to PWR_Regulator value */ - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS), Regulator); - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* Select Stop mode entry --------------------------------------------------*/ - if(STOPEntry == PWR_STOPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __SEV(); - __WFE(); - __WFE(); - } - /* Reset SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Enters Standby mode. - * @note In Standby mode, all I/O pins are high impedance except for: - * - Reset pad (still available) - * - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC - * Alarm out, or RTC clock calibration out. - * - RTC_AF2 pin (PI8) if configured for tamper or time-stamp. - * - WKUP pin 1 (PA0) if enabled. - * @retval None - */ -void HAL_PWR_EnterSTANDBYMode(void) -{ - /* Select Standby mode */ - SET_BIT(PWR->CR, PWR_CR_PDDS); - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* This option is used to ensure that store operations are completed */ -#if defined ( __CC_ARM) - __force_stores(); -#endif - /* Request Wait For Interrupt */ - __WFI(); -} - -/** - * @brief This function handles the PWR PVD interrupt request. - * @note This API should be called under the PVD_IRQHandler(). - * @retval None - */ -void HAL_PWR_PVD_IRQHandler(void) -{ - /* Check PWR Exti flag */ - if(__HAL_PWR_PVD_EXTI_GET_FLAG() != RESET) - { - /* PWR PVD interrupt user callback */ - HAL_PWR_PVDCallback(); - - /* Clear PWR Exti pending bit */ - __HAL_PWR_PVD_EXTI_CLEAR_FLAG(); - } -} - -/** - * @brief PWR PVD interrupt callback - * @retval None - */ -__weak void HAL_PWR_PVDCallback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_PWR_PVDCallback could be implemented in the user file - */ -} - -/** - * @brief Indicates Sleep-On-Exit when returning from Handler mode to Thread mode. - * @note Set SLEEPONEXIT bit of SCR register. When this bit is set, the processor - * re-enters SLEEP mode when an interruption handling is over. - * Setting this bit is useful when the processor is expected to run only on - * interruptions handling. - * @retval None - */ -void HAL_PWR_EnableSleepOnExit(void) -{ - /* Set SLEEPONEXIT bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Disables Sleep-On-Exit feature when returning from Handler mode to Thread mode. - * @note Clears SLEEPONEXIT bit of SCR register. When this bit is set, the processor - * re-enters SLEEP mode when an interruption handling is over. - * @retval None - */ -void HAL_PWR_DisableSleepOnExit(void) -{ - /* Clear SLEEPONEXIT bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Enables CORTEX M4 SEVONPEND bit. - * @note Sets SEVONPEND bit of SCR register. When this bit is set, this causes - * WFE to wake up when an interrupt moves from inactive to pended. - * @retval None - */ -void HAL_PWR_EnableSEVOnPend(void) -{ - /* Set SEVONPEND bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @brief Disables CORTEX M4 SEVONPEND bit. - * @note Clears SEVONPEND bit of SCR register. When this bit is set, this causes - * WFE to wake up when an interrupt moves from inactive to pended. - * @retval None - */ -void HAL_PWR_DisableSEVOnPend(void) -{ - /* Clear SEVONPEND bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_PWR_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr.c + * @author MCD Application Team + * @brief PWR HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Power Controller (PWR) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PWR PWR + * @brief PWR HAL module driver + * @{ + */ + +#ifdef HAL_PWR_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup PWR_Private_Constants + * @{ + */ + +/** @defgroup PWR_PVD_Mode_Mask PWR PVD Mode Mask + * @{ + */ +#define PVD_MODE_IT 0x00010000U +#define PVD_MODE_EVT 0x00020000U +#define PVD_RISING_EDGE 0x00000001U +#define PVD_FALLING_EDGE 0x00000002U +/** + * @} + */ + +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup PWR_Exported_Functions PWR Exported Functions + * @{ + */ + +/** @defgroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and de-initialization functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + After reset, the backup domain (RTC registers, RTC backup data + registers and backup SRAM) is protected against possible unwanted + write accesses. + To enable access to the RTC Domain and RTC registers, proceed as follows: + (+) Enable the Power Controller (PWR) APB1 interface clock using the + __HAL_RCC_PWR_CLK_ENABLE() macro. + (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the HAL PWR peripheral registers to their default reset values. + * @retval None + */ +void HAL_PWR_DeInit(void) +{ + __HAL_RCC_PWR_FORCE_RESET(); + __HAL_RCC_PWR_RELEASE_RESET(); +} + +/** + * @brief Enables access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @note The following sequence is required to bypass the delay between + * DBP bit programming and the effective enabling of the backup domain. + * Please check the Errata Sheet for more details under "Possible delay + * in backup domain protection disabling/enabling after programming the + * DBP bit" section. + * @retval None + */ +void HAL_PWR_EnableBkUpAccess(void) +{ + __IO uint32_t dummyread; + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)ENABLE; + dummyread = PWR->CR; + UNUSED(dummyread); +} + +/** + * @brief Disables access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @note The following sequence is required to bypass the delay between + * DBP bit programming and the effective disabling of the backup domain. + * Please check the Errata Sheet for more details under "Possible delay + * in backup domain protection disabling/enabling after programming the + * DBP bit" section. + * @retval None + */ +void HAL_PWR_DisableBkUpAccess(void) +{ + __IO uint32_t dummyread; + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)DISABLE; + dummyread = PWR->CR; + UNUSED(dummyread); +} + +/** + * @} + */ + +/** @defgroup PWR_Exported_Functions_Group2 Peripheral Control functions + * @brief Low Power modes configuration functions + * +@verbatim + + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + + *** PVD configuration *** + ========================= + [..] + (+) The PVD is used to monitor the VDD power supply by comparing it to a + threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR). + (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower + than the PVD threshold. This event is internally connected to the EXTI + line16 and can generate an interrupt if enabled. This is done through + __HAL_PWR_PVD_EXTI_ENABLE_IT() macro. + (+) The PVD is stopped in Standby mode. + + *** Wake-up pin configuration *** + ================================ + [..] + (+) Wake-up pin is used to wake up the system from Standby mode. This pin is + forced in input pull-down configuration and is active on rising edges. + (+) There is one Wake-up pin: Wake-up Pin 1 on PA.00. + (++) For STM32F446xx there are two Wake-Up pins: Pin1 on PA.00 and Pin2 on PC.13 + (++) For STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx there are three Wake-Up pins: Pin1 on PA.00, Pin2 on PC.00 and Pin3 on PC.01 + + *** Low Power modes configuration *** + ===================================== + [..] + The devices feature 3 low-power modes: + (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running. + (+) Stop mode: all clocks are stopped, regulator running, regulator + in low power mode + (+) Standby mode: 1.2V domain powered off. + + *** Sleep mode *** + ================== + [..] + (+) Entry: + The Sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI) + functions with + (++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction + (++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction + + -@@- The Regulator parameter is not used for the STM32F4 family + and is kept as parameter just to maintain compatibility with the + lower power families (STM32L). + (+) Exit: + Any peripheral interrupt acknowledged by the nested vectored interrupt + controller (NVIC) can wake up the device from Sleep mode. + + *** Stop mode *** + ================= + [..] + In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI, + and the HSE RC oscillators are disabled. Internal SRAM and register contents + are preserved. + The voltage regulator can be configured either in normal or low-power mode. + To minimize the consumption In Stop mode, FLASH can be powered off before + entering the Stop mode using the HAL_PWREx_EnableFlashPowerDown() function. + It can be switched on again by software after exiting the Stop mode using + the HAL_PWREx_DisableFlashPowerDown() function. + + (+) Entry: + The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON) + function with: + (++) Main regulator ON. + (++) Low Power regulator ON. + (+) Exit: + Any EXTI Line (Internal or External) configured in Interrupt/Event mode. + + *** Standby mode *** + ==================== + [..] + (+) + The Standby mode allows to achieve the lowest power consumption. It is based + on the Cortex-M4 deep sleep mode, with the voltage regulator disabled. + The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and + the HSE oscillator are also switched off. SRAM and register contents are lost + except for the RTC registers, RTC backup registers, backup SRAM and Standby + circuitry. + + The voltage regulator is OFF. + + (++) Entry: + (+++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function. + (++) Exit: + (+++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wake-up, + tamper event, time-stamp event, external reset in NRST pin, IWDG reset. + + *** Auto-wake-up (AWU) from low-power mode *** + ============================================= + [..] + + (+) The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC + Wake-up event, a tamper event or a time-stamp event, without depending on + an external interrupt (Auto-wake-up mode). + + (+) RTC auto-wake-up (AWU) from the Stop and Standby modes + + (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to + configure the RTC to generate the RTC alarm using the HAL_RTC_SetAlarm_IT() function. + + (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it + is necessary to configure the RTC to detect the tamper or time stamp event using the + HAL_RTCEx_SetTimeStamp_IT() or HAL_RTCEx_SetTamper_IT() functions. + + (++) To wake up from the Stop mode with an RTC Wake-up event, it is necessary to + configure the RTC to generate the RTC Wake-up event using the HAL_RTCEx_SetWakeUpTimer_IT() function. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param sConfigPVD pointer to an PWR_PVDTypeDef structure that contains the configuration + * information for the PVD. + * @note Refer to the electrical characteristics of your device datasheet for + * more details about the voltage threshold corresponding to each + * detection level. + * @retval None + */ +void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD) +{ + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel)); + assert_param(IS_PWR_PVD_MODE(sConfigPVD->Mode)); + + /* Set PLS[7:5] bits according to PVDLevel value */ + MODIFY_REG(PWR->CR, PWR_CR_PLS, sConfigPVD->PVDLevel); + + /* Clear any previous config. Keep it clear if no event or IT mode is selected */ + __HAL_PWR_PVD_EXTI_DISABLE_EVENT(); + __HAL_PWR_PVD_EXTI_DISABLE_IT(); + __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE(); + __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); + + /* Configure interrupt mode */ + if((sConfigPVD->Mode & PVD_MODE_IT) == PVD_MODE_IT) + { + __HAL_PWR_PVD_EXTI_ENABLE_IT(); + } + + /* Configure event mode */ + if((sConfigPVD->Mode & PVD_MODE_EVT) == PVD_MODE_EVT) + { + __HAL_PWR_PVD_EXTI_ENABLE_EVENT(); + } + + /* Configure the edge */ + if((sConfigPVD->Mode & PVD_RISING_EDGE) == PVD_RISING_EDGE) + { + __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE(); + } + + if((sConfigPVD->Mode & PVD_FALLING_EDGE) == PVD_FALLING_EDGE) + { + __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE(); + } +} + +/** + * @brief Enables the Power Voltage Detector(PVD). + * @retval None + */ +void HAL_PWR_EnablePVD(void) +{ + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Power Voltage Detector(PVD). + * @retval None + */ +void HAL_PWR_DisablePVD(void) +{ + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)DISABLE; +} + +/** + * @brief Enables the Wake-up PINx functionality. + * @param WakeUpPinx Specifies the Power Wake-Up pin to enable. + * This parameter can be one of the following values: + * @arg PWR_WAKEUP_PIN1 + * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @retval None + */ +void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx) +{ + /* Check the parameter */ + assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); + + /* Enable the wake up pin */ + SET_BIT(PWR->CSR, WakeUpPinx); +} + +/** + * @brief Disables the Wake-up PINx functionality. + * @param WakeUpPinx Specifies the Power Wake-Up pin to disable. + * This parameter can be one of the following values: + * @arg PWR_WAKEUP_PIN1 + * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @retval None + */ +void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx) +{ + /* Check the parameter */ + assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); + + /* Disable the wake up pin */ + CLEAR_BIT(PWR->CSR, WakeUpPinx); +} + +/** + * @brief Enters Sleep mode. + * + * @note In Sleep mode, all I/O pins keep the same state as in Run mode. + * + * @note In Sleep mode, the systick is stopped to avoid exit from this mode with + * systick interrupt when used as time base for Timeout + * + * @param Regulator Specifies the regulator state in SLEEP mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_ON: SLEEP mode with regulator ON + * @arg PWR_LOWPOWERREGULATOR_ON: SLEEP mode with low power regulator ON + * @note This parameter is not used for the STM32F4 family and is kept as parameter + * just to maintain compatibility with the lower power families. + * @param SLEEPEntry Specifies if SLEEP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction + * @arg PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction + * @retval None + */ +void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry) +{ + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(Regulator)); + assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); + + /* Clear SLEEPDEEP bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* Select SLEEP mode entry -------------------------------------------------*/ + if(SLEEPEntry == PWR_SLEEPENTRY_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __SEV(); + __WFE(); + __WFE(); + } +} + +/** + * @brief Enters Stop mode. + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * @note When exiting Stop mode by issuing an interrupt or a wake-up event, + * the HSI RC oscillator is selected as system clock. + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * @param Regulator Specifies the regulator state in Stop mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_ON: Stop mode with regulator ON + * @arg PWR_LOWPOWERREGULATOR_ON: Stop mode with low power regulator ON + * @param STOPEntry Specifies if Stop mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPENTRY_WFI: Enter Stop mode with WFI instruction + * @arg PWR_STOPENTRY_WFE: Enter Stop mode with WFE instruction + * @retval None + */ +void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry) +{ + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(Regulator)); + assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); + + /* Select the regulator state in Stop mode: Set PDDS and LPDS bits according to PWR_Regulator value */ + MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS), Regulator); + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* Select Stop mode entry --------------------------------------------------*/ + if(STOPEntry == PWR_STOPENTRY_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __SEV(); + __WFE(); + __WFE(); + } + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); +} + +/** + * @brief Enters Standby mode. + * @note In Standby mode, all I/O pins are high impedance except for: + * - Reset pad (still available) + * - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC + * Alarm out, or RTC clock calibration out. + * - RTC_AF2 pin (PI8) if configured for tamper or time-stamp. + * - WKUP pin 1 (PA0) if enabled. + * @retval None + */ +void HAL_PWR_EnterSTANDBYMode(void) +{ + /* Select Standby mode */ + SET_BIT(PWR->CR, PWR_CR_PDDS); + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @brief This function handles the PWR PVD interrupt request. + * @note This API should be called under the PVD_IRQHandler(). + * @retval None + */ +void HAL_PWR_PVD_IRQHandler(void) +{ + /* Check PWR Exti flag */ + if(__HAL_PWR_PVD_EXTI_GET_FLAG() != RESET) + { + /* PWR PVD interrupt user callback */ + HAL_PWR_PVDCallback(); + + /* Clear PWR Exti pending bit */ + __HAL_PWR_PVD_EXTI_CLEAR_FLAG(); + } +} + +/** + * @brief PWR PVD interrupt callback + * @retval None + */ +__weak void HAL_PWR_PVDCallback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_PWR_PVDCallback could be implemented in the user file + */ +} + +/** + * @brief Indicates Sleep-On-Exit when returning from Handler mode to Thread mode. + * @note Set SLEEPONEXIT bit of SCR register. When this bit is set, the processor + * re-enters SLEEP mode when an interruption handling is over. + * Setting this bit is useful when the processor is expected to run only on + * interruptions handling. + * @retval None + */ +void HAL_PWR_EnableSleepOnExit(void) +{ + /* Set SLEEPONEXIT bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Disables Sleep-On-Exit feature when returning from Handler mode to Thread mode. + * @note Clears SLEEPONEXIT bit of SCR register. When this bit is set, the processor + * re-enters SLEEP mode when an interruption handling is over. + * @retval None + */ +void HAL_PWR_DisableSleepOnExit(void) +{ + /* Clear SLEEPONEXIT bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Enables CORTEX M4 SEVONPEND bit. + * @note Sets SEVONPEND bit of SCR register. When this bit is set, this causes + * WFE to wake up when an interrupt moves from inactive to pended. + * @retval None + */ +void HAL_PWR_EnableSEVOnPend(void) +{ + /* Set SEVONPEND bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @brief Disables CORTEX M4 SEVONPEND bit. + * @note Clears SEVONPEND bit of SCR register. When this bit is set, this causes + * WFE to wake up when an interrupt moves from inactive to pended. + * @retval None + */ +void HAL_PWR_DisableSEVOnPend(void) +{ + /* Clear SEVONPEND bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_PWR_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c index 77f9c35..1acca55 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c @@ -1,600 +1,600 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr_ex.c - * @author MCD Application Team - * @brief Extended PWR HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of PWR extension peripheral: - * + Peripheral Extended features functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PWREx PWREx - * @brief PWR HAL module driver - * @{ - */ - -#ifdef HAL_PWR_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup PWREx_Private_Constants - * @{ - */ -#define PWR_OVERDRIVE_TIMEOUT_VALUE 1000U -#define PWR_UDERDRIVE_TIMEOUT_VALUE 1000U -#define PWR_BKPREG_TIMEOUT_VALUE 1000U -#define PWR_VOSRDY_TIMEOUT_VALUE 1000U -/** - * @} - */ - - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Functions PWREx Exported Functions - * @{ - */ - -/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended features functions - * @brief Peripheral Extended features functions - * -@verbatim - - =============================================================================== - ##### Peripheral extended features functions ##### - =============================================================================== - - *** Main and Backup Regulators configuration *** - ================================================ - [..] - (+) The backup domain includes 4 Kbytes of backup SRAM accessible only from - the CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is - retained even in Standby or VBAT mode when the low power backup regulator - is enabled. It can be considered as an internal EEPROM when VBAT is - always present. You can use the HAL_PWREx_EnableBkUpReg() function to - enable the low power backup regulator. - - (+) When the backup domain is supplied by VDD (analog switch connected to VDD) - the backup SRAM is powered from VDD which replaces the VBAT power supply to - save battery life. - - (+) The backup SRAM is not mass erased by a tamper event. It is read - protected to prevent confidential data, such as cryptographic private - key, from being accessed. The backup SRAM can be erased only through - the Flash interface when a protection level change from level 1 to - level 0 is requested. - -@- Refer to the description of Read protection (RDP) in the Flash - programming manual. - - (+) The main internal regulator can be configured to have a tradeoff between - performance and power consumption when the device does not operate at - the maximum frequency. This is done through __HAL_PWR_MAINREGULATORMODE_CONFIG() - macro which configure VOS bit in PWR_CR register - - Refer to the product datasheets for more details. - - *** FLASH Power Down configuration **** - ======================================= - [..] - (+) By setting the FPDS bit in the PWR_CR register by using the - HAL_PWREx_EnableFlashPowerDown() function, the Flash memory also enters power - down mode when the device enters Stop mode. When the Flash memory - is in power down mode, an additional startup delay is incurred when - waking up from Stop mode. - - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, the scale can be modified only when the PLL - is OFF and the HSI or HSE clock source is selected as system clock. - The new value programmed is active only when the PLL is ON. - When the PLL is OFF, the voltage scale 3 is automatically selected. - Refer to the datasheets for more details. - - *** Over-Drive and Under-Drive configuration **** - ================================================= - [..] - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Run mode: the main regulator has - 2 operating modes available: - (++) Normal mode: The CPU and core logic operate at maximum frequency at a given - voltage scaling (scale 1, scale 2 or scale 3) - (++) Over-drive mode: This mode allows the CPU and the core logic to operate at a - higher frequency than the normal mode for a given voltage scaling (scale 1, - scale 2 or scale 3). This mode is enabled through HAL_PWREx_EnableOverDrive() function and - disabled by HAL_PWREx_DisableOverDrive() function, to enter or exit from Over-drive mode please follow - the sequence described in Reference manual. - - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Stop mode: the main regulator or low power regulator - supplies a low power voltage to the 1.2V domain, thus preserving the content of registers - and internal SRAM. 2 operating modes are available: - (++) Normal mode: the 1.2V domain is preserved in nominal leakage mode. This mode is only - available when the main regulator or the low power regulator is used in Scale 3 or - low voltage mode. - (++) Under-drive mode: the 1.2V domain is preserved in reduced leakage mode. This mode is only - available when the main regulator or the low power regulator is in low voltage mode. - -@endverbatim - * @{ - */ - -/** - * @brief Enables the Backup Regulator. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void) -{ - uint32_t tickstart = 0U; - - *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)ENABLE; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till Backup regulator ready flag is set */ - while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) == RESET) - { - if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Disables the Backup Regulator. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void) -{ - uint32_t tickstart = 0U; - - *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)DISABLE; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till Backup regulator ready flag is set */ - while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) != RESET) - { - if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Enables the Flash Power Down in Stop mode. - * @retval None - */ -void HAL_PWREx_EnableFlashPowerDown(void) -{ - *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Flash Power Down in Stop mode. - * @retval None - */ -void HAL_PWREx_DisableFlashPowerDown(void) -{ - *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)DISABLE; -} - -/** - * @brief Return Voltage Scaling Range. - * @retval The configured scale for the regulator voltage(VOS bit field). - * The returned value can be one of the following: - * - @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * - @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * - @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode - */ -uint32_t HAL_PWREx_GetVoltageRange(void) -{ - return (PWR->CR & PWR_CR_VOS); -} - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief Configures the main internal regulator output voltage. - * @param VoltageScaling specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption. - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, - * the maximum value of fHCLK = 168 MHz. - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, - * the maximum value of fHCLK = 144 MHz. - * @note When moving from Range 1 to Range 2, the system frequency must be decreased to - * a value below 144 MHz before calling HAL_PWREx_ConfigVoltageScaling() API. - * When moving from Range 2 to Range 1, the system frequency can be increased to - * a value up to 168 MHz after calling HAL_PWREx_ConfigVoltageScaling() API. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) -{ - uint32_t tickstart = 0U; - - assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); - - /* Enable PWR RCC Clock Peripheral */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Set Range */ - __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) - { - if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || \ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Configures the main internal regulator output voltage. - * @param VoltageScaling specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption. - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, - * the maximum value of fHCLK is 168 MHz. It can be extended to - * 180 MHz by activating the over-drive mode. - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, - * the maximum value of fHCLK is 144 MHz. It can be extended to, - * 168 MHz by activating the over-drive mode. - * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output range 3 mode, - * the maximum value of fHCLK is 120 MHz. - * @note To update the system clock frequency(SYSCLK): - * - Set the HSI or HSE as system clock frequency using the HAL_RCC_ClockConfig(). - * - Call the HAL_RCC_OscConfig() to configure the PLL. - * - Call HAL_PWREx_ConfigVoltageScaling() API to adjust the voltage scale. - * - Set the new system clock frequency using the HAL_RCC_ClockConfig(). - * @note The scale can be modified only when the HSI or HSE clock source is selected - * as system clock source, otherwise the API returns HAL_ERROR. - * @note When the PLL is OFF, the voltage scale 3 is automatically selected and the VOS bits - * value in the PWR_CR1 register are not taken in account. - * @note This API forces the PLL state ON to allow the possibility to configure the voltage scale 1 or 2. - * @note The new voltage scale is active only when the PLL is ON. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) -{ - uint32_t tickstart = 0U; - - assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); - - /* Enable PWR RCC Clock Peripheral */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - /* Disable the main PLL */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - /* Wait till PLL is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Set Range */ - __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); - - /* Enable the main PLL */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) - { - if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - return HAL_ERROR; - } - - return HAL_OK; -} -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Enables Main Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_EnableMainRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables Main Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xxdevices. - * @retval None - */ -void HAL_PWREx_DisableMainRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)DISABLE; -} - -/** - * @brief Enables Low Power Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_EnableLowRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables Low Power Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_DisableLowRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE; -} - -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F412Zx || STM32F412Rx || STM32F412Vx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Activates the Over-Drive mode. - * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * This mode allows the CPU and the core logic to operate at a higher frequency - * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). - * @note It is recommended to enter or exit Over-drive mode when the application is not running - * critical tasks and when the system clock source is either HSI or HSE. - * During the Over-drive switch activation, no peripheral clocks should be enabled. - * The peripheral clocks must be enabled once the Over-drive mode is activated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void) -{ - uint32_t tickstart = 0U; - - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable the Over-drive to extend the clock frequency to 180 Mhz */ - __HAL_PWR_OVERDRIVE_ENABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Enable the Over-drive switch */ - __HAL_PWR_OVERDRIVESWITCHING_ENABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) - { - if((HAL_GetTick() - tickstart ) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Deactivates the Over-Drive mode. - * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * This mode allows the CPU and the core logic to operate at a higher frequency - * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). - * @note It is recommended to enter or exit Over-drive mode when the application is not running - * critical tasks and when the system clock source is either HSI or HSE. - * During the Over-drive switch activation, no peripheral clocks should be enabled. - * The peripheral clocks must be enabled once the Over-drive mode is activated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void) -{ - uint32_t tickstart = 0U; - - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Disable the Over-drive switch */ - __HAL_PWR_OVERDRIVESWITCHING_DISABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Disable the Over-drive */ - __HAL_PWR_OVERDRIVE_DISABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Enters in Under-Drive STOP mode. - * - * @note This mode is only available for STM32F42xxx/STM32F43xxx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * - * @note This mode can be selected only when the Under-Drive is already active - * - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main regulator or the low power regulator - * is in low voltage mode - * - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - * - * @note In Stop mode, all I/O pins keep the same state as in Run mode. - * - * @note When exiting Stop mode by issuing an interrupt or a wake-up event, - * the HSI RC oscillator is selected as system clock. - * - * @note When the voltage regulator operates in low power mode, an additional - * startup delay is incurred when waking up from Stop mode. - * By keeping the internal regulator ON during Stop mode, the consumption - * is higher although the startup time is reduced. - * - * @param Regulator specifies the regulator state in STOP mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_UNDERDRIVE_ON: Main Regulator in under-drive mode - * and Flash memory in power-down when the device is in Stop under-drive mode - * @arg PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON: Low Power Regulator in under-drive mode - * and Flash memory in power-down when the device is in Stop under-drive mode - * @param STOPEntry specifies if STOP mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_SLEEPENTRY_WFI: enter STOP mode with WFI instruction - * @arg PWR_SLEEPENTRY_WFE: enter STOP mode with WFE instruction - * @retval None - */ -HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry) -{ - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR_UNDERDRIVE(Regulator)); - assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); - - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Enable the Under-drive Mode ---------------------------------------------*/ - /* Clear Under-drive flag */ - __HAL_PWR_CLEAR_ODRUDR_FLAG(); - - /* Enable the Under-drive */ - __HAL_PWR_UNDERDRIVE_ENABLE(); - - /* Select the regulator state in STOP mode ---------------------------------*/ - tmpreg1 = PWR->CR; - /* Clear PDDS, LPDS, MRLUDS and LPLUDS bits */ - tmpreg1 &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_MRUDS); - - /* Set LPDS, MRLUDS and LPLUDS bits according to PWR_Regulator value */ - tmpreg1 |= Regulator; - - /* Store the new value */ - PWR->CR = tmpreg1; - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; - - /* Select STOP mode entry --------------------------------------------------*/ - if(STOPEntry == PWR_SLEEPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __WFE(); - } - /* Reset SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); - - return HAL_OK; -} - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_PWR_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr_ex.c + * @author MCD Application Team + * @brief Extended PWR HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of PWR extension peripheral: + * + Peripheral Extended features functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PWREx PWREx + * @brief PWR HAL module driver + * @{ + */ + +#ifdef HAL_PWR_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup PWREx_Private_Constants + * @{ + */ +#define PWR_OVERDRIVE_TIMEOUT_VALUE 1000U +#define PWR_UDERDRIVE_TIMEOUT_VALUE 1000U +#define PWR_BKPREG_TIMEOUT_VALUE 1000U +#define PWR_VOSRDY_TIMEOUT_VALUE 1000U +/** + * @} + */ + + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup PWREx_Exported_Functions PWREx Exported Functions + * @{ + */ + +/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended features functions + * @brief Peripheral Extended features functions + * +@verbatim + + =============================================================================== + ##### Peripheral extended features functions ##### + =============================================================================== + + *** Main and Backup Regulators configuration *** + ================================================ + [..] + (+) The backup domain includes 4 Kbytes of backup SRAM accessible only from + the CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is + retained even in Standby or VBAT mode when the low power backup regulator + is enabled. It can be considered as an internal EEPROM when VBAT is + always present. You can use the HAL_PWREx_EnableBkUpReg() function to + enable the low power backup regulator. + + (+) When the backup domain is supplied by VDD (analog switch connected to VDD) + the backup SRAM is powered from VDD which replaces the VBAT power supply to + save battery life. + + (+) The backup SRAM is not mass erased by a tamper event. It is read + protected to prevent confidential data, such as cryptographic private + key, from being accessed. The backup SRAM can be erased only through + the Flash interface when a protection level change from level 1 to + level 0 is requested. + -@- Refer to the description of Read protection (RDP) in the Flash + programming manual. + + (+) The main internal regulator can be configured to have a tradeoff between + performance and power consumption when the device does not operate at + the maximum frequency. This is done through __HAL_PWR_MAINREGULATORMODE_CONFIG() + macro which configure VOS bit in PWR_CR register + + Refer to the product datasheets for more details. + + *** FLASH Power Down configuration **** + ======================================= + [..] + (+) By setting the FPDS bit in the PWR_CR register by using the + HAL_PWREx_EnableFlashPowerDown() function, the Flash memory also enters power + down mode when the device enters Stop mode. When the Flash memory + is in power down mode, an additional startup delay is incurred when + waking up from Stop mode. + + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, the scale can be modified only when the PLL + is OFF and the HSI or HSE clock source is selected as system clock. + The new value programmed is active only when the PLL is ON. + When the PLL is OFF, the voltage scale 3 is automatically selected. + Refer to the datasheets for more details. + + *** Over-Drive and Under-Drive configuration **** + ================================================= + [..] + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Run mode: the main regulator has + 2 operating modes available: + (++) Normal mode: The CPU and core logic operate at maximum frequency at a given + voltage scaling (scale 1, scale 2 or scale 3) + (++) Over-drive mode: This mode allows the CPU and the core logic to operate at a + higher frequency than the normal mode for a given voltage scaling (scale 1, + scale 2 or scale 3). This mode is enabled through HAL_PWREx_EnableOverDrive() function and + disabled by HAL_PWREx_DisableOverDrive() function, to enter or exit from Over-drive mode please follow + the sequence described in Reference manual. + + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Stop mode: the main regulator or low power regulator + supplies a low power voltage to the 1.2V domain, thus preserving the content of registers + and internal SRAM. 2 operating modes are available: + (++) Normal mode: the 1.2V domain is preserved in nominal leakage mode. This mode is only + available when the main regulator or the low power regulator is used in Scale 3 or + low voltage mode. + (++) Under-drive mode: the 1.2V domain is preserved in reduced leakage mode. This mode is only + available when the main regulator or the low power regulator is in low voltage mode. + +@endverbatim + * @{ + */ + +/** + * @brief Enables the Backup Regulator. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void) +{ + uint32_t tickstart = 0U; + + *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)ENABLE; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till Backup regulator ready flag is set */ + while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) == RESET) + { + if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Disables the Backup Regulator. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void) +{ + uint32_t tickstart = 0U; + + *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)DISABLE; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till Backup regulator ready flag is set */ + while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) != RESET) + { + if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Enables the Flash Power Down in Stop mode. + * @retval None + */ +void HAL_PWREx_EnableFlashPowerDown(void) +{ + *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Flash Power Down in Stop mode. + * @retval None + */ +void HAL_PWREx_DisableFlashPowerDown(void) +{ + *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)DISABLE; +} + +/** + * @brief Return Voltage Scaling Range. + * @retval The configured scale for the regulator voltage(VOS bit field). + * The returned value can be one of the following: + * - @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode + * - @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode + * - @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode + */ +uint32_t HAL_PWREx_GetVoltageRange(void) +{ + return (PWR->CR & PWR_CR_VOS); +} + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) +/** + * @brief Configures the main internal regulator output voltage. + * @param VoltageScaling specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption. + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, + * the maximum value of fHCLK = 168 MHz. + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, + * the maximum value of fHCLK = 144 MHz. + * @note When moving from Range 1 to Range 2, the system frequency must be decreased to + * a value below 144 MHz before calling HAL_PWREx_ConfigVoltageScaling() API. + * When moving from Range 2 to Range 1, the system frequency can be increased to + * a value up to 168 MHz after calling HAL_PWREx_ConfigVoltageScaling() API. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) +{ + uint32_t tickstart = 0U; + + assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); + + /* Enable PWR RCC Clock Peripheral */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Set Range */ + __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) + { + if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || \ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Configures the main internal regulator output voltage. + * @param VoltageScaling specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption. + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, + * the maximum value of fHCLK is 168 MHz. It can be extended to + * 180 MHz by activating the over-drive mode. + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, + * the maximum value of fHCLK is 144 MHz. It can be extended to, + * 168 MHz by activating the over-drive mode. + * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output range 3 mode, + * the maximum value of fHCLK is 120 MHz. + * @note To update the system clock frequency(SYSCLK): + * - Set the HSI or HSE as system clock frequency using the HAL_RCC_ClockConfig(). + * - Call the HAL_RCC_OscConfig() to configure the PLL. + * - Call HAL_PWREx_ConfigVoltageScaling() API to adjust the voltage scale. + * - Set the new system clock frequency using the HAL_RCC_ClockConfig(). + * @note The scale can be modified only when the HSI or HSE clock source is selected + * as system clock source, otherwise the API returns HAL_ERROR. + * @note When the PLL is OFF, the voltage scale 3 is automatically selected and the VOS bits + * value in the PWR_CR1 register are not taken in account. + * @note This API forces the PLL state ON to allow the possibility to configure the voltage scale 1 or 2. + * @note The new voltage scale is active only when the PLL is ON. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) +{ + uint32_t tickstart = 0U; + + assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); + + /* Enable PWR RCC Clock Peripheral */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + /* Disable the main PLL */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + /* Wait till PLL is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Set Range */ + __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); + + /* Enable the main PLL */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) + { + if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + return HAL_ERROR; + } + + return HAL_OK; +} +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Enables Main Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_EnableMainRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables Main Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xxdevices. + * @retval None + */ +void HAL_PWREx_DisableMainRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)DISABLE; +} + +/** + * @brief Enables Low Power Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_EnableLowRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables Low Power Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_DisableLowRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE; +} + +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F412Zx || STM32F412Rx || STM32F412Vx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Activates the Over-Drive mode. + * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * This mode allows the CPU and the core logic to operate at a higher frequency + * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). + * @note It is recommended to enter or exit Over-drive mode when the application is not running + * critical tasks and when the system clock source is either HSI or HSE. + * During the Over-drive switch activation, no peripheral clocks should be enabled. + * The peripheral clocks must be enabled once the Over-drive mode is activated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void) +{ + uint32_t tickstart = 0U; + + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable the Over-drive to extend the clock frequency to 180 Mhz */ + __HAL_PWR_OVERDRIVE_ENABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Enable the Over-drive switch */ + __HAL_PWR_OVERDRIVESWITCHING_ENABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) + { + if((HAL_GetTick() - tickstart ) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Deactivates the Over-Drive mode. + * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * This mode allows the CPU and the core logic to operate at a higher frequency + * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). + * @note It is recommended to enter or exit Over-drive mode when the application is not running + * critical tasks and when the system clock source is either HSI or HSE. + * During the Over-drive switch activation, no peripheral clocks should be enabled. + * The peripheral clocks must be enabled once the Over-drive mode is activated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void) +{ + uint32_t tickstart = 0U; + + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Disable the Over-drive switch */ + __HAL_PWR_OVERDRIVESWITCHING_DISABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Disable the Over-drive */ + __HAL_PWR_OVERDRIVE_DISABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Enters in Under-Drive STOP mode. + * + * @note This mode is only available for STM32F42xxx/STM32F43xxx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * + * @note This mode can be selected only when the Under-Drive is already active + * + * @note This mode is enabled only with STOP low power mode. + * In this mode, the 1.2V domain is preserved in reduced leakage mode. This + * mode is only available when the main regulator or the low power regulator + * is in low voltage mode + * + * @note If the Under-drive mode was enabled, it is automatically disabled after + * exiting Stop mode. + * When the voltage regulator operates in Under-drive mode, an additional + * startup delay is induced when waking up from Stop mode. + * + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * + * @note When exiting Stop mode by issuing an interrupt or a wake-up event, + * the HSI RC oscillator is selected as system clock. + * + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * + * @param Regulator specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_UNDERDRIVE_ON: Main Regulator in under-drive mode + * and Flash memory in power-down when the device is in Stop under-drive mode + * @arg PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON: Low Power Regulator in under-drive mode + * and Flash memory in power-down when the device is in Stop under-drive mode + * @param STOPEntry specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_SLEEPENTRY_WFI: enter STOP mode with WFI instruction + * @arg PWR_SLEEPENTRY_WFE: enter STOP mode with WFE instruction + * @retval None + */ +HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry) +{ + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR_UNDERDRIVE(Regulator)); + assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); + + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Enable the Under-drive Mode ---------------------------------------------*/ + /* Clear Under-drive flag */ + __HAL_PWR_CLEAR_ODRUDR_FLAG(); + + /* Enable the Under-drive */ + __HAL_PWR_UNDERDRIVE_ENABLE(); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg1 = PWR->CR; + /* Clear PDDS, LPDS, MRLUDS and LPLUDS bits */ + tmpreg1 &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_MRUDS); + + /* Set LPDS, MRLUDS and LPLUDS bits according to PWR_Regulator value */ + tmpreg1 |= Regulator; + + /* Store the new value */ + PWR->CR = tmpreg1; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + /* Select STOP mode entry --------------------------------------------------*/ + if(STOPEntry == PWR_SLEEPENTRY_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); + + return HAL_OK; +} + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_PWR_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c index f187348..79364b6 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c @@ -1,1122 +1,1122 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc.c - * @author MCD Application Team - * @brief RCC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Reset and Clock Control (RCC) peripheral: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - @verbatim - ============================================================================== - ##### RCC specific features ##### - ============================================================================== - [..] - After reset the device is running from Internal High Speed oscillator - (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache - and I-Cache are disabled, and all peripherals are off except internal - SRAM, Flash and JTAG. - (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; - all peripherals mapped on these busses are running at HSI speed. - (+) The clock for all peripherals is switched off, except the SRAM and FLASH. - (+) All GPIOs are in input floating state, except the JTAG pins which - are assigned to be used for debug purpose. - - [..] - Once the device started from reset, the user application has to: - (+) Configure the clock source to be used to drive the System clock - (if the application needs higher frequency/performance) - (+) Configure the System clock frequency and Flash settings - (+) Configure the AHB and APB busses prescalers - (+) Enable the clock for the peripheral(s) to be used - (+) Configure the clock source(s) for peripherals which clocks are not - derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG) - - ##### RCC Limitations ##### - ============================================================================== - [..] - A delay between an RCC peripheral clock enable and the effective peripheral - enabling should be taken into account in order to manage the peripheral read/write - from/to registers. - (+) This delay depends on the peripheral mapping. - (+) If peripheral is mapped on AHB: the delay is 2 AHB clock cycle - after the clock enable bit is set on the hardware register - (+) If peripheral is mapped on APB: the delay is 2 APB clock cycle - after the clock enable bit is set on the hardware register - - [..] - Implemented Workaround: - (+) For AHB & APB peripherals, a dummy read to the peripheral register has been - inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro. - - @endverbatim - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RCC RCC - * @brief RCC HAL module driver - * @{ - */ - -#ifdef HAL_RCC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup RCC_Private_Constants - * @{ - */ - -/* Private macro -------------------------------------------------------------*/ -#define __MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() -#define MCO1_GPIO_PORT GPIOA -#define MCO1_PIN GPIO_PIN_8 - -#define __MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE() -#define MCO2_GPIO_PORT GPIOC -#define MCO2_PIN GPIO_PIN_9 -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup RCC_Private_Variables RCC Private Variables - * @{ - */ -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup RCC_Exported_Functions RCC Exported Functions - * @{ - */ - -/** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to configure the internal/external oscillators - (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1 - and APB2). - - [..] Internal/external clock and PLL configuration - (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through - the PLL as System clock source. - - (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC - clock source. - - (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or - through the PLL as System clock source. Can be used also as RTC clock source. - - (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. - - (#) PLL (clocked by HSI or HSE), featuring two different output clocks: - (++) The first output is used to generate the high speed system clock (up to 168 MHz) - (++) The second output is used to generate the clock for the USB OTG FS (48 MHz), - the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz). - - (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE() - and if a HSE clock failure occurs(HSE used directly or through PLL as System - clock source), the System clocks automatically switched to HSI and an interrupt - is generated if enabled. The interrupt is linked to the Cortex-M4 NMI - (Non-Maskable Interrupt) exception vector. - - (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL - clock (through a configurable prescaler) on PA8 pin. - - (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S - clock (through a configurable prescaler) on PC9 pin. - - [..] System, AHB and APB busses clocks configuration - (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, - HSE and PLL. - The AHB clock (HCLK) is derived from System clock through configurable - prescaler and used to clock the CPU, memory and peripherals mapped - on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived - from AHB clock through configurable prescalers and used to clock - the peripherals mapped on these busses. You can use - "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks. - - (#) For the STM32F405xx/07xx and STM32F415xx/17xx devices, the maximum - frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 84 MHz and PCLK1 42 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F42xxx, STM32F43xxx, STM32F446xx, STM32F469xx and STM32F479xx devices, - the maximum frequency of the SYSCLK and HCLK is 180 MHz, PCLK2 90 MHz and PCLK1 45 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F401xx, the maximum frequency of the SYSCLK and HCLK is 84 MHz, - PCLK2 84 MHz and PCLK1 42 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F41xxx, the maximum frequency of the SYSCLK and HCLK is 100 MHz, - PCLK2 100 MHz and PCLK1 50 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - -@endverbatim - * @{ - */ - -/** - * @brief Resets the RCC clock configuration to the default reset state. - * @note The default reset state of the clock configuration is given below: - * - HSI ON and used as system clock source - * - HSE and PLL OFF - * - AHB, APB1 and APB2 prescaler set to 1. - * - CSS, MCO1 and MCO2 OFF - * - All interrupts disabled - * @note This function doesn't modify the configuration of the - * - Peripheral clocks - * - LSI, LSE and RTC clocks - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_RCC_DeInit(void) -{ - return HAL_OK; -} - -/** - * @brief Initializes the RCC Oscillators according to the specified parameters in the - * RCC_OscInitTypeDef. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC Oscillators. - * @note The PLL is not disabled when used as system clock. - * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not - * supported by this API. User should request a transition to LSE Off - * first and then LSE On or LSE Bypass. - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not - * supported by this API. User should request a transition to HSE Off - * first and then HSE On or HSE Bypass. - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - uint32_t tickstart, pll_config; - - /* Check Null pointer */ - if(RCC_OscInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); - /*------------------------------- HSE Configuration ------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - { - /* Check the parameters */ - assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); - /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) - { - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - { - return HAL_ERROR; - } - } - else - { - /* Set the new HSE configuration ---------------------------------------*/ - __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - - /* Check the HSE State */ - if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till HSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till HSE is bypassed or disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*----------------------------- HSI Configuration --------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - { - /* Check the parameters */ - assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); - assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); - - /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) - { - /* When HSI is used as system clock it will not disabled */ - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - { - return HAL_ERROR; - } - /* Otherwise, just the calibration is allowed */ - else - { - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - } - else - { - /* Check the HSI State */ - if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - { - /* Enable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Adjusts the Internal High Speed oscillator (HSI) calibration value. */ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - else - { - /* Disable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*------------------------------ LSI Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - { - /* Check the parameters */ - assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); - - /* Check the LSI State */ - if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - { - /* Enable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - /*------------------------------ LSE Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - { - FlagStatus pwrclkchanged = RESET; - - /* Check the parameters */ - assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); - - /* Update LSE configuration in Backup Domain control register */ - /* Requires to enable write access to Backup Domain of necessary */ - if(__HAL_RCC_PWR_IS_CLK_DISABLED()) - { - __HAL_RCC_PWR_CLK_ENABLE(); - pwrclkchanged = SET; - } - - if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - /* Enable write access to Backup domain */ - SET_BIT(PWR->CR, PWR_CR_DBP); - - /* Wait for Backup domain Write protection disable */ - tickstart = HAL_GetTick(); - - while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Set the new LSE configuration -----------------------------------------*/ - __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - /* Check the LSE State */ - if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Restore clock configuration if changed */ - if(pwrclkchanged == SET) - { - __HAL_RCC_PWR_CLK_DISABLE(); - } - } - /*-------------------------------- PLL Configuration -----------------------*/ - /* Check the parameters */ - assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); - if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) - { - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - { - /* Check the parameters */ - assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); - assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); - assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); - assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); - assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); - - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Configure the main PLL clock source, multiplication and division factors. */ - WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ - RCC_OscInitStruct->PLL.PLLM | \ - (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ - (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ - (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))); - /* Enable the main PLL. */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - else - { - /* Check if there is a request to disable the PLL used as System clock source */ - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) - { - return HAL_ERROR; - } - else - { - /* Do not return HAL_ERROR if request repeats the current configuration */ - pll_config = RCC->PLLCFGR; -#if defined (RCC_PLLCFGR_PLLR) - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) -#else - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) -#endif - { - return HAL_ERROR; - } - } - } - } - return HAL_OK; -} - -/** - * @brief Initializes the CPU, AHB and APB busses clocks according to the specified - * parameters in the RCC_ClkInitStruct. - * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC peripheral. - * @param FLatency FLASH Latency, this parameter depend on device selected - * - * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency - * and updated by HAL_RCC_GetHCLKFreq() function called within this function - * - * @note The HSI is used (enabled by hardware) as system clock source after - * startup from Reset, wake-up from STOP and STANDBY mode, or in case - * of failure of the HSE used directly or indirectly as system clock - * (if the Clock Security System CSS is enabled). - * - * @note A switch from one clock source to another occurs only if the target - * clock source is ready (clock stable after startup delay or PLL locked). - * If a clock source which is not yet ready is selected, the switch will - * occur when the clock source will be ready. - * - * @note Depending on the device voltage range, the software has to set correctly - * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency - * (for more details refer to section above "Initialization/de-initialization functions") - * @retval None - */ -HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency) -{ - uint32_t tickstart; - - /* Check Null pointer */ - if(RCC_ClkInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType)); - assert_param(IS_FLASH_LATENCY(FLatency)); - - /* To correctly read data from FLASH memory, the number of wait states (LATENCY) - must be correctly programmed according to the frequency of the CPU clock - (HCLK) and the supply voltage of the device. */ - - /* Increasing the number of wait states because of higher CPU frequency */ - if(FLatency > __HAL_FLASH_GET_LATENCY()) - { - /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ - __HAL_FLASH_SET_LATENCY(FLatency); - - /* Check that the new number of wait states is taken into account to access the Flash - memory by reading the FLASH_ACR register */ - if(__HAL_FLASH_GET_LATENCY() != FLatency) - { - return HAL_ERROR; - } - } - - /*-------------------------- HCLK Configuration --------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) - { - /* Set the highest APBx dividers in order to ensure that we do not go through - a non-spec phase whatever we decrease or increase HCLK. */ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - { - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); - } - - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - { - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); - } - - assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider); - } - - /*------------------------- SYSCLK Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) - { - assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); - - /* HSE is selected as System Clock Source */ - if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) - { - /* Check the HSE ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - return HAL_ERROR; - } - } - /* PLL is selected as System Clock Source */ - else if((RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) || - (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLRCLK)) - { - /* Check the PLL ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - return HAL_ERROR; - } - } - /* HSI is selected as System Clock Source */ - else - { - /* Check the HSI ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - return HAL_ERROR; - } - } - - __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - { - if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Decreasing the number of wait states because of lower CPU frequency */ - if(FLatency < __HAL_FLASH_GET_LATENCY()) - { - /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ - __HAL_FLASH_SET_LATENCY(FLatency); - - /* Check that the new number of wait states is taken into account to access the Flash - memory by reading the FLASH_ACR register */ - if(__HAL_FLASH_GET_LATENCY() != FLatency) - { - return HAL_ERROR; - } - } - - /*-------------------------- PCLK1 Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - { - assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); - } - - /*-------------------------- PCLK2 Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - { - assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U)); - } - - /* Update the SystemCoreClock global variable */ - SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; - - /* Configure the source of time base considering new system clocks settings */ - HAL_InitTick (uwTickPrio); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions - * @brief RCC clocks control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the RCC Clocks - frequencies. - -@endverbatim - * @{ - */ - -/** - * @brief Selects the clock source to output on MCO1 pin(PA8) or on MCO2 pin(PC9). - * @note PA8/PC9 should be configured in alternate function mode. - * @param RCC_MCOx specifies the output direction for the clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO1: Clock source to output on MCO1 pin(PA8). - * @arg RCC_MCO2: Clock source to output on MCO2 pin(PC9). - * @param RCC_MCOSource specifies the clock source to output. - * This parameter can be one of the following values: - * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source - * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices - * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source - * @param RCC_MCODiv specifies the MCOx prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - * @note For STM32F410Rx devices to output I2SCLK clock on MCO2 you should have - * at last one of the SPI clocks enabled (SPI1, SPI2 or SPI5). - * @retval None - */ -void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv) -{ - GPIO_InitTypeDef GPIO_InitStruct; - /* Check the parameters */ - assert_param(IS_RCC_MCO(RCC_MCOx)); - assert_param(IS_RCC_MCODIV(RCC_MCODiv)); - /* RCC_MCO1 */ - if(RCC_MCOx == RCC_MCO1) - { - assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource)); - - /* MCO1 Clock Enable */ - __MCO1_CLK_ENABLE(); - - /* Configure the MCO1 pin in alternate function mode */ - GPIO_InitStruct.Pin = MCO1_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF0_MCO; - HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct); - - /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv)); - - /* This RCC MCO1 enable feature is available only on STM32F410xx devices */ -#if defined(RCC_CFGR_MCO1EN) - __HAL_RCC_MCO1_ENABLE(); -#endif /* RCC_CFGR_MCO1EN */ - } -#if defined(RCC_CFGR_MCO2) - else - { - assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource)); - - /* MCO2 Clock Enable */ - __MCO2_CLK_ENABLE(); - - /* Configure the MCO2 pin in alternate function mode */ - GPIO_InitStruct.Pin = MCO2_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF0_MCO; - HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct); - - /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3U))); - - /* This RCC MCO2 enable feature is available only on STM32F410Rx devices */ -#if defined(RCC_CFGR_MCO2EN) - __HAL_RCC_MCO2_ENABLE(); -#endif /* RCC_CFGR_MCO2EN */ - } -#endif /* RCC_CFGR_MCO2 */ -} - -/** - * @brief Enables the Clock Security System. - * @note If a failure is detected on the HSE oscillator clock, this oscillator - * is automatically disabled and an interrupt is generated to inform the - * software about the failure (Clock Security System Interrupt, CSSI), - * allowing the MCU to perform rescue operations. The CSSI is linked to - * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. - * @retval None - */ -void HAL_RCC_EnableCSS(void) -{ - *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Clock Security System. - * @retval None - */ -void HAL_RCC_DisableCSS(void) -{ - *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE; -} - -/** - * @brief Returns the SYSCLK frequency - * - * @note The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) - * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) - * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * @note The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @note This function can be used by the user application to compute the - * baudrate for the communication peripherals or configure other parameters. - * - * @note Each time SYSCLK changes, this function must be called to update the - * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * - * @retval SYSCLK frequency - */ -__weak uint32_t HAL_RCC_GetSysClockFreq(void) -{ - uint32_t pllm = 0U, pllvco = 0U, pllp = 0U; - uint32_t sysclockfreq = 0U; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (RCC->CFGR & RCC_CFGR_SWS) - { - case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ - { - sysclockfreq = HSI_VALUE; - break; - } - case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ - { - sysclockfreq = HSE_VALUE; - break; - } - case RCC_CFGR_SWS_PLL: /* PLL used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLP */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); - - sysclockfreq = pllvco/pllp; - break; - } - default: - { - sysclockfreq = HSI_VALUE; - break; - } - } - return sysclockfreq; -} - -/** - * @brief Returns the HCLK frequency - * @note Each time HCLK changes, this function must be called to update the - * right HCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency - * and updated within this function - * @retval HCLK frequency - */ -uint32_t HAL_RCC_GetHCLKFreq(void) -{ - return SystemCoreClock; -} - -/** - * @brief Returns the PCLK1 frequency - * @note Each time PCLK1 changes, this function must be called to update the - * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect. - * @retval PCLK1 frequency - */ -uint32_t HAL_RCC_GetPCLK1Freq(void) -{ - /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/ - return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> RCC_CFGR_PPRE1_Pos]); -} - -/** - * @brief Returns the PCLK2 frequency - * @note Each time PCLK2 changes, this function must be called to update the - * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect. - * @retval PCLK2 frequency - */ -uint32_t HAL_RCC_GetPCLK2Freq(void) -{ - /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/ - return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> RCC_CFGR_PPRE2_Pos]); -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * will be configured. - * @retval None - */ -__weak void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - /* Set all possible values for the Oscillator type parameter ---------------*/ - RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; - - /* Get the HSE configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) - { - RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; - } - else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) - { - RCC_OscInitStruct->HSEState = RCC_HSE_ON; - } - else - { - RCC_OscInitStruct->HSEState = RCC_HSE_OFF; - } - - /* Get the HSI configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) - { - RCC_OscInitStruct->HSIState = RCC_HSI_ON; - } - else - { - RCC_OscInitStruct->HSIState = RCC_HSI_OFF; - } - - RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); - - /* Get the LSE configuration -----------------------------------------------*/ - if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) - { - RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; - } - else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) - { - RCC_OscInitStruct->LSEState = RCC_LSE_ON; - } - else - { - RCC_OscInitStruct->LSEState = RCC_LSE_OFF; - } - - /* Get the LSI configuration -----------------------------------------------*/ - if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) - { - RCC_OscInitStruct->LSIState = RCC_LSI_ON; - } - else - { - RCC_OscInitStruct->LSIState = RCC_LSI_OFF; - } - - /* Get the PLL configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; - } - else - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; - } - RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); - RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); - RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); - RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); - RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); -} - -/** - * @brief Configures the RCC_ClkInitStruct according to the internal - * RCC configuration registers. - * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that - * will be configured. - * @param pFLatency Pointer on the Flash Latency. - * @retval None - */ -void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency) -{ - /* Set all possible values for the Clock type parameter --------------------*/ - RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; - - /* Get the SYSCLK configuration --------------------------------------------*/ - RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW); - - /* Get the HCLK configuration ----------------------------------------------*/ - RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE); - - /* Get the APB1 configuration ----------------------------------------------*/ - RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1); - - /* Get the APB2 configuration ----------------------------------------------*/ - RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U); - - /* Get the Flash Wait State (Latency) configuration ------------------------*/ - *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY); -} - -/** - * @brief This function handles the RCC CSS interrupt request. - * @note This API should be called under the NMI_Handler(). - * @retval None - */ -void HAL_RCC_NMI_IRQHandler(void) -{ - /* Check RCC CSSF flag */ - if(__HAL_RCC_GET_IT(RCC_IT_CSS)) - { - /* RCC Clock Security System interrupt user callback */ - HAL_RCC_CSSCallback(); - - /* Clear RCC CSS pending bit */ - __HAL_RCC_CLEAR_IT(RCC_IT_CSS); - } -} - -/** - * @brief RCC Clock Security System interrupt callback - * @retval None - */ -__weak void HAL_RCC_CSSCallback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RCC_CSSCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_RCC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc.c + * @author MCD Application Team + * @brief RCC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Reset and Clock Control (RCC) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + @verbatim + ============================================================================== + ##### RCC specific features ##### + ============================================================================== + [..] + After reset the device is running from Internal High Speed oscillator + (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache + and I-Cache are disabled, and all peripherals are off except internal + SRAM, Flash and JTAG. + (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; + all peripherals mapped on these busses are running at HSI speed. + (+) The clock for all peripherals is switched off, except the SRAM and FLASH. + (+) All GPIOs are in input floating state, except the JTAG pins which + are assigned to be used for debug purpose. + + [..] + Once the device started from reset, the user application has to: + (+) Configure the clock source to be used to drive the System clock + (if the application needs higher frequency/performance) + (+) Configure the System clock frequency and Flash settings + (+) Configure the AHB and APB busses prescalers + (+) Enable the clock for the peripheral(s) to be used + (+) Configure the clock source(s) for peripherals which clocks are not + derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG) + + ##### RCC Limitations ##### + ============================================================================== + [..] + A delay between an RCC peripheral clock enable and the effective peripheral + enabling should be taken into account in order to manage the peripheral read/write + from/to registers. + (+) This delay depends on the peripheral mapping. + (+) If peripheral is mapped on AHB: the delay is 2 AHB clock cycle + after the clock enable bit is set on the hardware register + (+) If peripheral is mapped on APB: the delay is 2 APB clock cycle + after the clock enable bit is set on the hardware register + + [..] + Implemented Workaround: + (+) For AHB & APB peripherals, a dummy read to the peripheral register has been + inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro. + + @endverbatim + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RCC RCC + * @brief RCC HAL module driver + * @{ + */ + +#ifdef HAL_RCC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup RCC_Private_Constants + * @{ + */ + +/* Private macro -------------------------------------------------------------*/ +#define __MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() +#define MCO1_GPIO_PORT GPIOA +#define MCO1_PIN GPIO_PIN_8 + +#define __MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE() +#define MCO2_GPIO_PORT GPIOC +#define MCO2_PIN GPIO_PIN_9 +/** + * @} + */ + +/* Private variables ---------------------------------------------------------*/ +/** @defgroup RCC_Private_Variables RCC Private Variables + * @{ + */ +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RCC_Exported_Functions RCC Exported Functions + * @{ + */ + +/** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to configure the internal/external oscillators + (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1 + and APB2). + + [..] Internal/external clock and PLL configuration + (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through + the PLL as System clock source. + + (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC + clock source. + + (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or + through the PLL as System clock source. Can be used also as RTC clock source. + + (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. + + (#) PLL (clocked by HSI or HSE), featuring two different output clocks: + (++) The first output is used to generate the high speed system clock (up to 168 MHz) + (++) The second output is used to generate the clock for the USB OTG FS (48 MHz), + the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz). + + (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE() + and if a HSE clock failure occurs(HSE used directly or through PLL as System + clock source), the System clocks automatically switched to HSI and an interrupt + is generated if enabled. The interrupt is linked to the Cortex-M4 NMI + (Non-Maskable Interrupt) exception vector. + + (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL + clock (through a configurable prescaler) on PA8 pin. + + (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S + clock (through a configurable prescaler) on PC9 pin. + + [..] System, AHB and APB busses clocks configuration + (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, + HSE and PLL. + The AHB clock (HCLK) is derived from System clock through configurable + prescaler and used to clock the CPU, memory and peripherals mapped + on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived + from AHB clock through configurable prescalers and used to clock + the peripherals mapped on these busses. You can use + "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks. + + (#) For the STM32F405xx/07xx and STM32F415xx/17xx devices, the maximum + frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 84 MHz and PCLK1 42 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F42xxx, STM32F43xxx, STM32F446xx, STM32F469xx and STM32F479xx devices, + the maximum frequency of the SYSCLK and HCLK is 180 MHz, PCLK2 90 MHz and PCLK1 45 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F401xx, the maximum frequency of the SYSCLK and HCLK is 84 MHz, + PCLK2 84 MHz and PCLK1 42 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F41xxx, the maximum frequency of the SYSCLK and HCLK is 100 MHz, + PCLK2 100 MHz and PCLK1 50 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + +@endverbatim + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE and PLL OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO1 and MCO2 OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_RCC_DeInit(void) +{ + return HAL_OK; +} + +/** + * @brief Initializes the RCC Oscillators according to the specified parameters in the + * RCC_OscInitTypeDef. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC Oscillators. + * @note The PLL is not disabled when used as system clock. + * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not + * supported by this API. User should request a transition to LSE Off + * first and then LSE On or LSE Bypass. + * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not + * supported by this API. User should request a transition to HSE Off + * first and then HSE On or HSE Bypass. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + uint32_t tickstart, pll_config; + + /* Check Null pointer */ + if(RCC_OscInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); + /*------------------------------- HSE Configuration ------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) + { + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); + /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) + { + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + { + return HAL_ERROR; + } + } + else + { + /* Set the new HSE configuration ---------------------------------------*/ + __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); + + /* Check the HSE State */ + if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till HSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till HSE is bypassed or disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*----------------------------- HSI Configuration --------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) + { + /* Check the parameters */ + assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); + assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); + + /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) + { + /* When HSI is used as system clock it will not disabled */ + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) + { + return HAL_ERROR; + } + /* Otherwise, just the calibration is allowed */ + else + { + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + } + else + { + /* Check the HSI State */ + if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) + { + /* Enable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Adjusts the Internal High Speed oscillator (HSI) calibration value. */ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + else + { + /* Disable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*------------------------------ LSI Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) + { + /* Check the parameters */ + assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); + + /* Check the LSI State */ + if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) + { + /* Enable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + /*------------------------------ LSE Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) + { + FlagStatus pwrclkchanged = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); + + /* Update LSE configuration in Backup Domain control register */ + /* Requires to enable write access to Backup Domain of necessary */ + if(__HAL_RCC_PWR_IS_CLK_DISABLED()) + { + __HAL_RCC_PWR_CLK_ENABLE(); + pwrclkchanged = SET; + } + + if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + /* Enable write access to Backup domain */ + SET_BIT(PWR->CR, PWR_CR_DBP); + + /* Wait for Backup domain Write protection disable */ + tickstart = HAL_GetTick(); + + while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Set the new LSE configuration -----------------------------------------*/ + __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); + /* Check the LSE State */ + if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Restore clock configuration if changed */ + if(pwrclkchanged == SET) + { + __HAL_RCC_PWR_CLK_DISABLE(); + } + } + /*-------------------------------- PLL Configuration -----------------------*/ + /* Check the parameters */ + assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); + if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) + { + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) + { + /* Check the parameters */ + assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); + assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); + assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); + assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); + assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); + + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Configure the main PLL clock source, multiplication and division factors. */ + WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ + RCC_OscInitStruct->PLL.PLLM | \ + (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ + (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ + (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))); + /* Enable the main PLL. */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + else + { + /* Check if there is a request to disable the PLL used as System clock source */ + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) + { + return HAL_ERROR; + } + else + { + /* Do not return HAL_ERROR if request repeats the current configuration */ + pll_config = RCC->PLLCFGR; +#if defined (RCC_PLLCFGR_PLLR) + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) +#else + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) +#endif + { + return HAL_ERROR; + } + } + } + } + return HAL_OK; +} + +/** + * @brief Initializes the CPU, AHB and APB busses clocks according to the specified + * parameters in the RCC_ClkInitStruct. + * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC peripheral. + * @param FLatency FLASH Latency, this parameter depend on device selected + * + * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency + * and updated by HAL_RCC_GetHCLKFreq() function called within this function + * + * @note The HSI is used (enabled by hardware) as system clock source after + * startup from Reset, wake-up from STOP and STANDBY mode, or in case + * of failure of the HSE used directly or indirectly as system clock + * (if the Clock Security System CSS is enabled). + * + * @note A switch from one clock source to another occurs only if the target + * clock source is ready (clock stable after startup delay or PLL locked). + * If a clock source which is not yet ready is selected, the switch will + * occur when the clock source will be ready. + * + * @note Depending on the device voltage range, the software has to set correctly + * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency + * (for more details refer to section above "Initialization/de-initialization functions") + * @retval None + */ +HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency) +{ + uint32_t tickstart; + + /* Check Null pointer */ + if(RCC_ClkInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType)); + assert_param(IS_FLASH_LATENCY(FLatency)); + + /* To correctly read data from FLASH memory, the number of wait states (LATENCY) + must be correctly programmed according to the frequency of the CPU clock + (HCLK) and the supply voltage of the device. */ + + /* Increasing the number of wait states because of higher CPU frequency */ + if(FLatency > __HAL_FLASH_GET_LATENCY()) + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + + /* Check that the new number of wait states is taken into account to access the Flash + memory by reading the FLASH_ACR register */ + if(__HAL_FLASH_GET_LATENCY() != FLatency) + { + return HAL_ERROR; + } + } + + /*-------------------------- HCLK Configuration --------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) + { + /* Set the highest APBx dividers in order to ensure that we do not go through + a non-spec phase whatever we decrease or increase HCLK. */ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); + } + + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); + } + + assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider); + } + + /*------------------------- SYSCLK Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) + { + assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); + + /* HSE is selected as System Clock Source */ + if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) + { + /* Check the HSE ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + return HAL_ERROR; + } + } + /* PLL is selected as System Clock Source */ + else if((RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) || + (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLRCLK)) + { + /* Check the PLL ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + return HAL_ERROR; + } + } + /* HSI is selected as System Clock Source */ + else + { + /* Check the HSI ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + return HAL_ERROR; + } + } + + __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) + { + if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Decreasing the number of wait states because of lower CPU frequency */ + if(FLatency < __HAL_FLASH_GET_LATENCY()) + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + + /* Check that the new number of wait states is taken into account to access the Flash + memory by reading the FLASH_ACR register */ + if(__HAL_FLASH_GET_LATENCY() != FLatency) + { + return HAL_ERROR; + } + } + + /*-------------------------- PCLK1 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); + } + + /*-------------------------- PCLK2 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U)); + } + + /* Update the SystemCoreClock global variable */ + SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; + + /* Configure the source of time base considering new system clocks settings */ + HAL_InitTick (uwTickPrio); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions + * @brief RCC clocks control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the RCC Clocks + frequencies. + +@endverbatim + * @{ + */ + +/** + * @brief Selects the clock source to output on MCO1 pin(PA8) or on MCO2 pin(PC9). + * @note PA8/PC9 should be configured in alternate function mode. + * @param RCC_MCOx specifies the output direction for the clock source. + * This parameter can be one of the following values: + * @arg RCC_MCO1: Clock source to output on MCO1 pin(PA8). + * @arg RCC_MCO2: Clock source to output on MCO2 pin(PC9). + * @param RCC_MCOSource specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source + * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx + * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices + * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source + * @param RCC_MCODiv specifies the MCOx prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCODIV_1: no division applied to MCOx clock + * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock + * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock + * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock + * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock + * @note For STM32F410Rx devices to output I2SCLK clock on MCO2 you should have + * at last one of the SPI clocks enabled (SPI1, SPI2 or SPI5). + * @retval None + */ +void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv) +{ + GPIO_InitTypeDef GPIO_InitStruct; + /* Check the parameters */ + assert_param(IS_RCC_MCO(RCC_MCOx)); + assert_param(IS_RCC_MCODIV(RCC_MCODiv)); + /* RCC_MCO1 */ + if(RCC_MCOx == RCC_MCO1) + { + assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource)); + + /* MCO1 Clock Enable */ + __MCO1_CLK_ENABLE(); + + /* Configure the MCO1 pin in alternate function mode */ + GPIO_InitStruct.Pin = MCO1_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct); + + /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv)); + + /* This RCC MCO1 enable feature is available only on STM32F410xx devices */ +#if defined(RCC_CFGR_MCO1EN) + __HAL_RCC_MCO1_ENABLE(); +#endif /* RCC_CFGR_MCO1EN */ + } +#if defined(RCC_CFGR_MCO2) + else + { + assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource)); + + /* MCO2 Clock Enable */ + __MCO2_CLK_ENABLE(); + + /* Configure the MCO2 pin in alternate function mode */ + GPIO_InitStruct.Pin = MCO2_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct); + + /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3U))); + + /* This RCC MCO2 enable feature is available only on STM32F410Rx devices */ +#if defined(RCC_CFGR_MCO2EN) + __HAL_RCC_MCO2_ENABLE(); +#endif /* RCC_CFGR_MCO2EN */ + } +#endif /* RCC_CFGR_MCO2 */ +} + +/** + * @brief Enables the Clock Security System. + * @note If a failure is detected on the HSE oscillator clock, this oscillator + * is automatically disabled and an interrupt is generated to inform the + * software about the failure (Clock Security System Interrupt, CSSI), + * allowing the MCU to perform rescue operations. The CSSI is linked to + * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. + * @retval None + */ +void HAL_RCC_EnableCSS(void) +{ + *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Clock Security System. + * @retval None + */ +void HAL_RCC_DisableCSS(void) +{ + *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE; +} + +/** + * @brief Returns the SYSCLK frequency + * + * @note The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) + * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * + * @note Each time SYSCLK changes, this function must be called to update the + * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * + * @retval SYSCLK frequency + */ +__weak uint32_t HAL_RCC_GetSysClockFreq(void) +{ + uint32_t pllm = 0U, pllvco = 0U, pllp = 0U; + uint32_t sysclockfreq = 0U; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ + { + sysclockfreq = HSI_VALUE; + break; + } + case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ + { + sysclockfreq = HSE_VALUE; + break; + } + case RCC_CFGR_SWS_PLL: /* PLL used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLP */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); + + sysclockfreq = pllvco/pllp; + break; + } + default: + { + sysclockfreq = HSI_VALUE; + break; + } + } + return sysclockfreq; +} + +/** + * @brief Returns the HCLK frequency + * @note Each time HCLK changes, this function must be called to update the + * right HCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency + * and updated within this function + * @retval HCLK frequency + */ +uint32_t HAL_RCC_GetHCLKFreq(void) +{ + return SystemCoreClock; +} + +/** + * @brief Returns the PCLK1 frequency + * @note Each time PCLK1 changes, this function must be called to update the + * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect. + * @retval PCLK1 frequency + */ +uint32_t HAL_RCC_GetPCLK1Freq(void) +{ + /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/ + return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> RCC_CFGR_PPRE1_Pos]); +} + +/** + * @brief Returns the PCLK2 frequency + * @note Each time PCLK2 changes, this function must be called to update the + * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect. + * @retval PCLK2 frequency + */ +uint32_t HAL_RCC_GetPCLK2Freq(void) +{ + /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/ + return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> RCC_CFGR_PPRE2_Pos]); +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * will be configured. + * @retval None + */ +__weak void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + /* Set all possible values for the Oscillator type parameter ---------------*/ + RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; + + /* Get the HSE configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) + { + RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; + } + else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) + { + RCC_OscInitStruct->HSEState = RCC_HSE_ON; + } + else + { + RCC_OscInitStruct->HSEState = RCC_HSE_OFF; + } + + /* Get the HSI configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) + { + RCC_OscInitStruct->HSIState = RCC_HSI_ON; + } + else + { + RCC_OscInitStruct->HSIState = RCC_HSI_OFF; + } + + RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); + + /* Get the LSE configuration -----------------------------------------------*/ + if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) + { + RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; + } + else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) + { + RCC_OscInitStruct->LSEState = RCC_LSE_ON; + } + else + { + RCC_OscInitStruct->LSEState = RCC_LSE_OFF; + } + + /* Get the LSI configuration -----------------------------------------------*/ + if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) + { + RCC_OscInitStruct->LSIState = RCC_LSI_ON; + } + else + { + RCC_OscInitStruct->LSIState = RCC_LSI_OFF; + } + + /* Get the PLL configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; + } + else + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; + } + RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); + RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); + RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); + RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); +} + +/** + * @brief Configures the RCC_ClkInitStruct according to the internal + * RCC configuration registers. + * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that + * will be configured. + * @param pFLatency Pointer on the Flash Latency. + * @retval None + */ +void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency) +{ + /* Set all possible values for the Clock type parameter --------------------*/ + RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + + /* Get the SYSCLK configuration --------------------------------------------*/ + RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW); + + /* Get the HCLK configuration ----------------------------------------------*/ + RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE); + + /* Get the APB1 configuration ----------------------------------------------*/ + RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1); + + /* Get the APB2 configuration ----------------------------------------------*/ + RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U); + + /* Get the Flash Wait State (Latency) configuration ------------------------*/ + *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY); +} + +/** + * @brief This function handles the RCC CSS interrupt request. + * @note This API should be called under the NMI_Handler(). + * @retval None + */ +void HAL_RCC_NMI_IRQHandler(void) +{ + /* Check RCC CSSF flag */ + if(__HAL_RCC_GET_IT(RCC_IT_CSS)) + { + /* RCC Clock Security System interrupt user callback */ + HAL_RCC_CSSCallback(); + + /* Clear RCC CSS pending bit */ + __HAL_RCC_CLEAR_IT(RCC_IT_CSS); + } +} + +/** + * @brief RCC Clock Security System interrupt callback + * @retval None + */ +__weak void HAL_RCC_CSSCallback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RCC_CSSCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_RCC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c index 5076628..dd89656 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c @@ -1,3784 +1,3784 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc_ex.c - * @author MCD Application Team - * @brief Extension RCC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities RCC extension peripheral: - * + Extended Peripheral Control functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file in - * the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RCCEx RCCEx - * @brief RCCEx HAL module driver - * @{ - */ - -#ifdef HAL_RCC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup RCCEx_Private_Constants - * @{ - */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Functions RCCEx Exported Functions - * @{ - */ - -/** @defgroup RCCEx_Exported_Functions_Group1 Extended Peripheral Control functions - * @brief Extended Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Extended Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the RCC Clocks - frequencies. - [..] - (@) Important note: Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to - select the RTC clock source; in this case the Backup domain will be reset in - order to modify the RTC Clock source, as consequence RTC registers (including - the backup registers) and RCC_BDCR register are set to their reset values. - -@endverbatim - * @{ - */ - -#if defined(STM32F446xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - uint32_t plli2sp = 0U; - uint32_t plli2sq = 0U; - uint32_t plli2sr = 0U; - uint32_t pllsaip = 0U; - uint32_t pllsaiq = 0U; - uint32_t plli2sused = 0U; - uint32_t pllsaiused = 0U; - - /* Check the peripheral clock selection parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*------------------------ I2S APB1 configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- I2S APB2 configuration ----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*--------------------------- SAI1 configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*-------------------------- SAI2 configuration ----------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); - - /* Configure SAI2 Clock source */ - __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); - - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- RTC configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - /* Configure Timer Prescaler */ - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- FMPI2C1 Configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ CEC Configuration -------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) - { - /* Check the parameters */ - assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); - - /* Configure the CEC clock source */ - __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- CLK48 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the CLK48 clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - - /* Enable the PLLSAI when it's used as clock source for CLK48 */ - if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- SDIO Configuration -------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ SPDIFRX Configuration ---------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) - { - /* Check the parameters */ - assert_param(IS_RCC_SPDIFRXCLKSOURCE(PeriphClkInit->SpdifClockSelection)); - - /* Configure the SPDIFRX clock source */ - __HAL_RCC_SPDIFRX_CONFIG(PeriphClkInit->SpdifClockSelection); - /* Enable the PLLI2S when it's used as clock source for SPDIFRX */ - if(PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- PLLI2S Configuration ------------------------*/ - /* PLLI2S is configured when a peripheral will use it as source clock : SAI1, SAI2, I2S on APB1, - I2S on APB2 or SPDIFRX */ - if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) - { - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* check for common PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /*------ In Case of PLLI2S is selected as source clock for I2S -----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S))) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Read PLLI2SP/PLLI2SQ value from PLLI2SCFGR register (this value is not needed for I2S configuration) */ - plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - { - /* Check for PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - /* Check for PLLI2S/DIVQ parameters */ - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SP/PLLI2SR value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ - plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, PeriphClkInit->PLLI2S.PLLI2SQ, plli2sr); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*------ In Case of PLLI2S is selected as source clock for SPDIFRX -------*/ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) && (PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - plli2sq = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, plli2sq, plli2sr); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- PLLSAI Configuration -----------------------*/ - /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, CLK48 or SDIO */ - if(pllsaiused == 1U) - { - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIM_VALUE(PeriphClkInit->PLLSAI.PLLSAIM)); - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /*------ In Case of PLLSAI is selected as source clock for SAI -----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - { - /* check for PLLSAIQ Parameter */ - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - /* check for PLLSAI/DIVQ Parameter */ - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, 0U); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*------ In Case of PLLSAI is selected as source clock for CLK48 ---------*/ - /* In Case of PLLI2S is selected as source clock for CLK48 */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); - /* Read PLLSAIQ value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Configure the PLLSAI division factors */ - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLI2SN/PLLSAIM) */ - /* 48CLK = f(PLLSAI clock output) = f(VCO clock) / PLLSAIP */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, 0U); - } - - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_SAI1 | RCC_PERIPHCLK_SAI2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_FMPI2C1 |\ - RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO |\ - RCC_PERIPHCLK_SPDIFRX; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SP = (uint32_t)((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Get the PLLSAI Clock configuration --------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIM = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM) >> RCC_PLLSAICFGR_PLLSAIM_Pos); - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIP = (uint32_t)((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - - /* Get the SAI1 clock configuration ----------------------------------------*/ - PeriphClkInit->Sai1ClockSelection = __HAL_RCC_GET_SAI1_SOURCE(); - - /* Get the SAI2 clock configuration ----------------------------------------*/ - PeriphClkInit->Sai2ClockSelection = __HAL_RCC_GET_SAI2_SOURCE(); - - /* Get the I2S APB1 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); - - /* Get the I2S APB2 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); - - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the CEC clock configuration -----------------------------------------*/ - PeriphClkInit->CecClockSelection = __HAL_RCC_GET_CEC_SOURCE(); - - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the CLK48 clock configuration ----------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - /* Get the SPDIFRX clock configuration -------------------------------------*/ - PeriphClkInit->SpdifClockSelection = __HAL_RCC_GET_SPDIFRX_SOURCE(); - - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_SAI1: SAI1 peripheral clock - * @arg RCC_PERIPHCLK_SAI2: SAI2 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - uint32_t tmpreg1 = 0U; - /* This variable used to store the SAI clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - /* This variable used to store the SAI clock source */ - uint32_t saiclocksource = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_SAI1: - case RCC_PERIPHCLK_SAI2: - { - saiclocksource = RCC->DCKCFGR; - saiclocksource &= (RCC_DCKCFGR_SAI1SRC | RCC_DCKCFGR_SAI2SRC); - switch (saiclocksource) - { - case 0U: /* PLLSAI is the clock source for SAI*/ - { - /* Configure the PLLSAI division factor */ - /* PLLSAI_VCO Input = PLL_SOURCE/PLLSAIM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM))); - } - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - tmpreg1 = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; - frequency = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U))/(tmpreg1); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - tmpreg1 = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); - frequency = frequency/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC_0: /* PLLI2S is the clock source for SAI*/ - case RCC_DCKCFGR_SAI2SRC_0: /* PLLI2S is the clock source for SAI*/ - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM))); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - tmpreg1 = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; - frequency = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U))/(tmpreg1); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - tmpreg1 = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); - frequency = frequency/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC_1: /* PLLR is the clock source for SAI*/ - case RCC_DCKCFGR_SAI2SRC_1: /* PLLR is the clock source for SAI*/ - { - /* Configure the PLLI2S division factor */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - /* SAI_CLK_x = PLL_VCO Output/PLLR */ - tmpreg1 = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; - frequency = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U))/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC: /* External clock is the clock source for SAI*/ - { - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - case RCC_DCKCFGR_SAI2SRC: /* PLLSRC(HSE or HSI) is the clock source for SAI*/ - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - frequency = (uint32_t)(HSI_VALUE); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - frequency = (uint32_t)(HSE_VALUE); - } - break; - } - default : - { - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB1: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB1CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB2: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB2CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC, RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - uint32_t pllsaip = 0U; - uint32_t pllsaiq = 0U; - uint32_t pllsair = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*--------------------------- CLK48 Configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the CLK48 clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ SDIO Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ - /*------------------- Common configuration SAI/I2S -------------------------*/ - /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------- I2S configuration -------------------------------*/ - /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added - only for I2S configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) - { - /* Check the PLLI2S division factors */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Configure the PLLI2S multiplication and division factors */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ - /*----------------------- Common configuration SAI/LTDC --------------------*/ - /* In Case of SAI, LTDC or CLK48 Clock Configuration through PLLSAI, PLLSAIN division - factor is common parameters for these peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && - (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP))) - { - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) - { - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, pllsair); - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*---------------------------- LTDC configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) - { - assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); - assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, pllsaiq, PeriphClkInit->PLLSAI.PLLSAIR); - /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - } - - /*---------------------------- CLK48 configuration ------------------------*/ - /* Configure the PLLSAI when it is used as clock source for CLK48 */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == (RCC_PERIPHCLK_CLK48)) && - (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) - { - assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); - - /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* CLK48_CLK(first level) = PLLSAI_VCO Output/PLLSAIP */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, pllsair); - } - - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - - /*--------------------------------------------------------------------------*/ - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - return HAL_OK; -} - -/** - * @brief Configures the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI |\ - RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Get the PLLSAI Clock configuration --------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the CLK48 clock configuration -------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t plli2sq = 0U; -#endif /* STM32F413xx || STM32F423xx */ - uint32_t plli2sused = 0U; - - /* Check the peripheral clock selection parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*----------------------------------- I2S APB1 configuration ---------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------------- I2S APB2 configuration ---------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*----------------------- SAI1 Block A configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == (RCC_PERIPHCLK_SAIA)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAIACLKSOURCE(PeriphClkInit->SaiAClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(PeriphClkInit->SaiAClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLR) - { - /* Check for PLL/DIVR parameters */ - assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ - __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------- SAI1 Block B configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == (RCC_PERIPHCLK_SAIB)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAIBCLKSOURCE(PeriphClkInit->SaiBClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(PeriphClkInit->SaiBClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLR) - { - /* Check for PLL/DIVR parameters */ - assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ - __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); - } - } - /*--------------------------------------------------------------------------*/ -#endif /* STM32F413xx || STM32F423xx */ - - /*------------------------------------ RTC configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------ TIM configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - /* Configure Timer Prescaler */ - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- FMPI2C1 Configuration --------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- CLK48 Configuration ----------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - - /* Enable the PLLI2S when it's used as clock source for CLK48 */ - if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- SDIO Configuration -----------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------------------------- PLLI2S Configuration --------------*/ - /* PLLI2S is configured when a peripheral will use it as source clock : I2S on APB1 or - I2S on APB2*/ - if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) - { - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* check for common PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SCLKSOURCE(PeriphClkInit->PLLI2SSelection)); - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - /*-------------------- Set the PLL I2S clock -----------------------------*/ - __HAL_RCC_PLL_I2S_CONFIG(PeriphClkInit->PLLI2SSelection); - - /*------- In Case of PLLI2S is selected as source clock for I2S ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) && (PeriphClkInit->SdioClockSelection == RCC_SDIOCLKSOURCE_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ))) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == RCC_PERIPHCLK_SAIA) && (PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == RCC_PERIPHCLK_SAIB) && (PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR))) - { - /* Check for PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Check for PLLI2S/DIVR parameters */ - assert_param(IS_RCC_PLLI2S_DIVR_VALUE(PeriphClkInit->PLLI2SDivR)); - - /* Read PLLI2SQ value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ - plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLI2SDivR); - } -#endif /* STM32F413xx || STM32F423xx */ - - /*----------------- In Case of PLLI2S is just selected ------------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM1 clock source configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); - - /* Configure the DFSDM1 interface clock source */ - __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM1 Audio clock source configuration -------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); - - /* Configure the DFSDM1 Audio interface clock source */ - __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); - } - /*--------------------------------------------------------------------------*/ - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*-------------------- DFSDM2 clock source configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2) == RCC_PERIPHCLK_DFSDM2) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM2CLKSOURCE(PeriphClkInit->Dfsdm2ClockSelection)); - - /* Configure the DFSDM1 interface clock source */ - __HAL_RCC_DFSDM2_CONFIG(PeriphClkInit->Dfsdm2ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM2 Audio clock source configuration -------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2_AUDIO) == RCC_PERIPHCLK_DFSDM2_AUDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM2AUDIOCLKSOURCE(PeriphClkInit->Dfsdm2AudioClockSelection)); - - /* Configure the DFSDM1 Audio interface clock source */ - __HAL_RCC_DFSDM2AUDIO_CONFIG(PeriphClkInit->Dfsdm2AudioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- LPTIM1 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - { - /* Check the parameters */ - assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); - - /* Configure the LPTIM1 clock source */ - __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - } - /*--------------------------------------------------------------------------*/ -#endif /* STM32F413xx || STM32F423xx */ - - return HAL_OK; -} - -/** - * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ - RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ - RCC_PERIPHCLK_DFSDM1_AUDIO | RCC_PERIPHCLK_DFSDM2 |\ - RCC_PERIPHCLK_DFSDM2_AUDIO | RCC_PERIPHCLK_LPTIM1 |\ - RCC_PERIPHCLK_SAIA | RCC_PERIPHCLK_SAIB; -#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ - RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ - RCC_PERIPHCLK_DFSDM1_AUDIO; -#endif /* STM32F413xx || STM32F423xx */ - - - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); -#if defined(STM32F413xx) || defined(STM32F423xx) - /* Get the PLL/PLLI2S division factors -------------------------------------*/ - PeriphClkInit->PLLI2SDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) >> RCC_DCKCFGR_PLLI2SDIVR_Pos); - PeriphClkInit->PLLDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> RCC_DCKCFGR_PLLDIVR_Pos); -#endif /* STM32F413xx || STM32F423xx */ - - /* Get the I2S APB1 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); - - /* Get the I2S APB2 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); - - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the CLK48 clock configuration ---------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - /* Get the DFSDM1 clock configuration --------------------------------------*/ - PeriphClkInit->Dfsdm1ClockSelection = __HAL_RCC_GET_DFSDM1_SOURCE(); - - /* Get the DFSDM1 Audio clock configuration --------------------------------*/ - PeriphClkInit->Dfsdm1AudioClockSelection = __HAL_RCC_GET_DFSDM1AUDIO_SOURCE(); - -#if defined(STM32F413xx) || defined(STM32F423xx) - /* Get the DFSDM2 clock configuration --------------------------------------*/ - PeriphClkInit->Dfsdm2ClockSelection = __HAL_RCC_GET_DFSDM2_SOURCE(); - - /* Get the DFSDM2 Audio clock configuration --------------------------------*/ - PeriphClkInit->Dfsdm2AudioClockSelection = __HAL_RCC_GET_DFSDM2AUDIO_SOURCE(); - - /* Get the LPTIM1 clock configuration --------------------------------------*/ - PeriphClkInit->Lptim1ClockSelection = __HAL_RCC_GET_LPTIM1_SOURCE(); - - /* Get the SAI1 Block Aclock configuration ---------------------------------*/ - PeriphClkInit->SaiAClockSelection = __HAL_RCC_GET_SAI_BLOCKA_SOURCE(); - - /* Get the SAI1 Block B clock configuration --------------------------------*/ - PeriphClkInit->SaiBClockSelection = __HAL_RCC_GET_SAI_BLOCKB_SOURCE(); -#endif /* STM32F413xx || STM32F423xx */ - - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(I2S..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S_APB1: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLI2S: - { - if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - } - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB1CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB2: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLI2S: - { - if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - } - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB2CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the - * RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). - * - * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case - * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup - * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- FMPI2C1 Configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- LPTIM1 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - { - /* Check the parameters */ - assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); - - /* Configure the LPTIM1 clock source */ - __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - } - - /*---------------------------- I2S Configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPBCLKSOURCE(PeriphClkInit->I2SClockSelection)); - - /* Configure the I2S clock source */ - __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2SClockSelection); - } - - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_LPTIM1 | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; - - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the I2S clock configuration -----------------------------------------*/ - PeriphClkInit->I2SClockSelection = __HAL_RCC_GET_I2S_SOURCE(); - - -} -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPBCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPBCLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPBCLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ - /*----------------------- Common configuration SAI/I2S ---------------------*/ - /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- I2S configuration -------------------------*/ - /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added - only for I2S configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) - { - /* Check the PLLI2S division factors */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Configure the PLLI2S multiplication and division factors */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ - /*----------------------- Common configuration SAI/LTDC --------------------*/ - /* In Case of SAI or LTDC Clock Configuration through PLLSAI, PLLSAIN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC)) - { - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) - { - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIQ, tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*---------------------------- LTDC configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) - { - assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); - assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); - - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg1, PeriphClkInit->PLLSAI.PLLSAIR); - /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - } - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - return HAL_OK; -} - -/** - * @brief Configures the PeriphClkInit according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI | RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; - - /* Get the PLLI2S Clock configuration -----------------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Get the PLLSAI Clock configuration -----------------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors -----------------------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); - /* Get the RTC Clock configuration -----------------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the - * RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). - * - * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case - * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup - * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*---------------------------- I2S configuration ---------------------------*/ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); -#if defined(STM32F411xE) - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); -#endif /* STM32F411xE */ - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - -#if defined(STM32F411xE) - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SR); -#else - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); -#endif /* STM32F411xE */ - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_RTC; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); -#if defined(STM32F411xE) - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM); -#endif /* STM32F411xE */ - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { -#if defined(STM32F411xE) - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } -#else - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } -#endif /* STM32F411xE */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Select LSE mode - * - * @note This mode is only available for STM32F410xx/STM32F411xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. - * - * @param Mode specifies the LSE mode. - * This parameter can be one of the following values: - * @arg RCC_LSE_LOWPOWER_MODE: LSE oscillator in low power mode selection - * @arg RCC_LSE_HIGHDRIVE_MODE: LSE oscillator in High Drive mode selection - * @retval None - */ -void HAL_RCCEx_SelectLSEMode(uint8_t Mode) -{ - /* Check the parameters */ - assert_param(IS_RCC_LSE_MODE(Mode)); - if(Mode == RCC_LSE_HIGHDRIVE_MODE) - { - SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); - } - else - { - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); - } -} - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** @defgroup RCCEx_Exported_Functions_Group2 Extended Clock management functions - * @brief Extended Clock management functions - * -@verbatim - =============================================================================== - ##### Extended clock management functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the - activation or deactivation of PLLI2S, PLLSAI. -@endverbatim - * @{ - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Enable PLLI2S. - * @param PLLI2SInit pointer to an RCC_PLLI2SInitTypeDef structure that - * contains the configuration information for the PLLI2S - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit) -{ - uint32_t tickstart; - - /* Check for parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SInit->PLLI2SN)); - assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SInit->PLLI2SR)); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - assert_param(IS_RCC_PLLI2SM_VALUE(PLLI2SInit->PLLI2SM)); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -#if defined(RCC_PLLI2SCFGR_PLLI2SP) - assert_param(IS_RCC_PLLI2SP_VALUE(PLLI2SInit->PLLI2SP)); -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) - assert_param(IS_RCC_PLLI2SQ_VALUE(PLLI2SInit->PLLI2SQ)); -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - - /* Wait till PLLI2S is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Configure the PLLI2S division factors */ -#if defined(STM32F446xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SPCLK = PLLI2S_VCO / PLLI2SP */ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ - PLLI2SInit->PLLI2SP, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ - PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * PLLI2SN */ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F411xE) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); -#else - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x PLLI2SN */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); -#endif /* STM32F446xx */ - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - - /* Wait till PLLI2S is ready */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Disable PLLI2S. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void) -{ - uint32_t tickstart; - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - - /* Wait till PLLI2S is disabled */ - tickstart = HAL_GetTick(); - while(READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Enable PLLSAI. - * @param PLLSAIInit pointer to an RCC_PLLSAIInitTypeDef structure that - * contains the configuration information for the PLLSAI - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit) -{ - uint32_t tickstart; - - /* Check for parameters */ - assert_param(IS_RCC_PLLSAIN_VALUE(PLLSAIInit->PLLSAIN)); - assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIInit->PLLSAIQ)); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - assert_param(IS_RCC_PLLSAIM_VALUE(PLLSAIInit->PLLSAIM)); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -#if defined(RCC_PLLSAICFGR_PLLSAIP) - assert_param(IS_RCC_PLLSAIP_VALUE(PLLSAIInit->PLLSAIP)); -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#if defined(RCC_PLLSAICFGR_PLLSAIR) - assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIInit->PLLSAIR)); -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - - /* Disable the PLLSAI */ - __HAL_RCC_PLLSAI_DISABLE(); - - /* Wait till PLLSAI is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Configure the PLLSAI division factors */ -#if defined(STM32F446xx) - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLSAIN/PLLSAIM) */ - /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIM, PLLSAIInit->PLLSAIN, \ - PLLSAIInit->PLLSAIP, PLLSAIInit->PLLSAIQ, 0U); -#elif defined(STM32F469xx) || defined(STM32F479xx) - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * PLLSAIN */ - /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIP, \ - PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); -#else - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) x PLLSAIN */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); -#endif /* STM32F446xx */ - - /* Enable the PLLSAI */ - __HAL_RCC_PLLSAI_ENABLE(); - - /* Wait till PLLSAI is ready */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Disable PLLSAI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void) -{ - uint32_t tickstart; - - /* Disable the PLLSAI */ - __HAL_RCC_PLLSAI_DISABLE(); - - /* Wait till PLLSAI is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @} - */ - -#if defined(STM32F446xx) -/** - * @brief Returns the SYSCLK frequency - * - * @note This function implementation is valid only for STM32F446xx devices. - * @note This function add the PLL/PLLR System clock source - * - * @note The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) - * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) - * @note If SYSCLK source is PLL or PLLR, function returns values based on HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * @note The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @note This function can be used by the user application to compute the - * baudrate for the communication peripherals or configure other parameters. - * - * @note Each time SYSCLK changes, this function must be called to update the - * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * - * @retval SYSCLK frequency - */ -uint32_t HAL_RCC_GetSysClockFreq(void) -{ - uint32_t pllm = 0U; - uint32_t pllvco = 0U; - uint32_t pllp = 0U; - uint32_t pllr = 0U; - uint32_t sysclockfreq = 0U; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (RCC->CFGR & RCC_CFGR_SWS) - { - case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ - { - sysclockfreq = HSI_VALUE; - break; - } - case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ - { - sysclockfreq = HSE_VALUE; - break; - } - case RCC_CFGR_SWS_PLL: /* PLL/PLLP used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLP */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); - - sysclockfreq = pllvco/pllp; - break; - } - case RCC_CFGR_SWS_PLLR: /* PLL/PLLR used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLR */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllr = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); - - sysclockfreq = pllvco/pllr; - break; - } - default: - { - sysclockfreq = HSI_VALUE; - break; - } - } - return sysclockfreq; -} -#endif /* STM32F446xx */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @brief Resets the RCC clock configuration to the default reset state. - * @note The default reset state of the clock configuration is given below: - * - HSI ON and used as system clock source - * - HSE, PLL, PLLI2S and PLLSAI OFF - * - AHB, APB1 and APB2 prescaler set to 1. - * - CSS, MCO1 and MCO2 OFF - * - All interrupts disabled - * @note This function doesn't modify the configuration of the - * - Peripheral clocks - * - LSI, LSE and RTC clocks - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCC_DeInit(void) -{ - uint32_t tickstart; - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Set HSION bit to the reset value */ - SET_BIT(RCC->CR, RCC_CR_HSION); - - /* Wait till HSI is ready */ - while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET) - { - if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Set HSITRIM[4:0] bits to the reset value */ - SET_BIT(RCC->CR, RCC_CR_HSITRIM_4); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset CFGR register */ - CLEAR_REG(RCC->CFGR); - - /* Wait till clock switch is ready */ - while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RESET) - { - if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Clear HSEON, HSEBYP and CSSON bits */ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON); - - /* Wait till HSE is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Clear PLLON bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLON); - - /* Wait till PLL is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - -#if defined(RCC_PLLI2S_SUPPORT) - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset PLLI2SON bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); - - /* Wait till PLLI2S is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset PLLSAI bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); - - /* Wait till PLLSAI is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } -#endif /* RCC_PLLSAI_SUPPORT */ - - /* Once PLL, PLLI2S and PLLSAI are OFF, reset PLLCFGR register to default value */ -#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ - defined(STM32F423xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLR_1; -#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) - RCC->PLLCFGR = RCC_PLLCFGR_PLLR_0 | RCC_PLLCFGR_PLLR_1 | RCC_PLLCFGR_PLLR_2 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_0 | RCC_PLLCFGR_PLLQ_1 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLQ_3; -#else - RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2; -#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx || STM32F469xx || STM32F479xx */ - - /* Reset PLLI2SCFGR register to default value */ -#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ - defined(STM32F423xx) || defined(STM32F446xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F411xE) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; -#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx */ - - /* Reset PLLSAICFGR register */ -#if defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIR_1; -#elif defined(STM32F446xx) - RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2; -#endif /* STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F469xx || STM32F479xx */ - - /* Disable all interrupts */ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); - -#if defined(RCC_CIR_PLLI2SRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -#endif /* RCC_CIR_PLLI2SRDYIE */ - -#if defined(RCC_CIR_PLLSAIRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -#endif /* RCC_CIR_PLLSAIRDYIE */ - - /* Clear all interrupt flags */ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); - -#if defined(RCC_CIR_PLLI2SRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -#endif /* RCC_CIR_PLLI2SRDYC */ - -#if defined(RCC_CIR_PLLSAIRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -#endif /* RCC_CIR_PLLSAIRDYC */ - - /* Clear LSION bit */ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); - - /* Reset all CSR flags */ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); - - /* Update the SystemCoreClock global variable */ - SystemCoreClock = HSI_VALUE; - - /* Adapt Systick interrupt period */ - if(HAL_InitTick(uwTickPrio) != HAL_OK) - { - return HAL_ERROR; - } - else - { - return HAL_OK; - } -} - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Initializes the RCC Oscillators according to the specified parameters in the - * RCC_OscInitTypeDef. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC Oscillators. - * @note The PLL is not disabled when used as system clock. - * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not - * supported by this API. User should request a transition to LSE Off - * first and then LSE On or LSE Bypass. - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not - * supported by this API. User should request a transition to HSE Off - * first and then HSE On or HSE Bypass. - * @note This function add the PLL/PLLR factor management during PLL configuration this feature - * is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - uint32_t tickstart, pll_config; - - /* Check Null pointer */ - if(RCC_OscInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); - /*------------------------------- HSE Configuration ------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - { - /* Check the parameters */ - assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); - /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ -#if defined(STM32F446xx) - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) -#else - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) -#endif /* STM32F446xx */ - { - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - { - return HAL_ERROR; - } - } - else - { - /* Set the new HSE configuration ---------------------------------------*/ - __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - - /* Check the HSE State */ - if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSE is bypassed or disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*----------------------------- HSI Configuration --------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - { - /* Check the parameters */ - assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); - assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); - - /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ -#if defined(STM32F446xx) - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI)) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) -#else - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) -#endif /* STM32F446xx */ - { - /* When HSI is used as system clock it will not disabled */ - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - { - return HAL_ERROR; - } - /* Otherwise, just the calibration is allowed */ - else - { - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - } - else - { - /* Check the HSI State */ - if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - { - /* Enable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - else - { - /* Disable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*------------------------------ LSI Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - { - /* Check the parameters */ - assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); - - /* Check the LSI State */ - if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - { - /* Enable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - /*------------------------------ LSE Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - { - FlagStatus pwrclkchanged = RESET; - - /* Check the parameters */ - assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); - - /* Update LSE configuration in Backup Domain control register */ - /* Requires to enable write access to Backup Domain of necessary */ - if(__HAL_RCC_PWR_IS_CLK_DISABLED()) - { - __HAL_RCC_PWR_CLK_ENABLE(); - pwrclkchanged = SET; - } - - if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - /* Enable write access to Backup domain */ - SET_BIT(PWR->CR, PWR_CR_DBP); - - /* Wait for Backup domain Write protection disable */ - tickstart = HAL_GetTick(); - - while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Set the new LSE configuration -----------------------------------------*/ - __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - /* Check the LSE State */ - if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Restore clock configuration if changed */ - if(pwrclkchanged == SET) - { - __HAL_RCC_PWR_CLK_DISABLE(); - } - } - /*-------------------------------- PLL Configuration -----------------------*/ - /* Check the parameters */ - assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); - if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) - { - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - { - /* Check the parameters */ - assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); - assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); - assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); - assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); - assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); - assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); - - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Configure the main PLL clock source, multiplication and division factors. */ - WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ - RCC_OscInitStruct->PLL.PLLM | \ - (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ - (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ - (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos) | \ - (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))); - /* Enable the main PLL. */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - else - { - /* Check if there is a request to disable the PLL used as System clock source */ - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) - { - return HAL_ERROR; - } - else - { - /* Do not return HAL_ERROR if request repeats the current configuration */ - pll_config = RCC->PLLCFGR; -#if defined (RCC_PLLCFGR_PLLR) - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) -#else - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) -#endif - { - return HAL_ERROR; - } - } - } - } - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that will be configured. - * - * @note This function is only available in case of STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. - * @note This function add the PLL/PLLR factor management - * @retval None - */ -void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - /* Set all possible values for the Oscillator type parameter ---------------*/ - RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; - - /* Get the HSE configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) - { - RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; - } - else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) - { - RCC_OscInitStruct->HSEState = RCC_HSE_ON; - } - else - { - RCC_OscInitStruct->HSEState = RCC_HSE_OFF; - } - - /* Get the HSI configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) - { - RCC_OscInitStruct->HSIState = RCC_HSI_ON; - } - else - { - RCC_OscInitStruct->HSIState = RCC_HSI_OFF; - } - - RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); - - /* Get the LSE configuration -----------------------------------------------*/ - if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) - { - RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; - } - else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) - { - RCC_OscInitStruct->LSEState = RCC_LSE_ON; - } - else - { - RCC_OscInitStruct->LSEState = RCC_LSE_OFF; - } - - /* Get the LSI configuration -----------------------------------------------*/ - if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) - { - RCC_OscInitStruct->LSIState = RCC_LSI_ON; - } - else - { - RCC_OscInitStruct->LSIState = RCC_LSI_OFF; - } - - /* Get the PLL configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; - } - else - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; - } - RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); - RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); - RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); - RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); - RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); - RCC_OscInitStruct->PLL.PLLR = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); -} -#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#endif /* HAL_RCC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc_ex.c + * @author MCD Application Team + * @brief Extension RCC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities RCC extension peripheral: + * + Extended Peripheral Control functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file in + * the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RCCEx RCCEx + * @brief RCCEx HAL module driver + * @{ + */ + +#ifdef HAL_RCC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup RCCEx_Private_Constants + * @{ + */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup RCCEx_Exported_Functions RCCEx Exported Functions + * @{ + */ + +/** @defgroup RCCEx_Exported_Functions_Group1 Extended Peripheral Control functions + * @brief Extended Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Extended Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the RCC Clocks + frequencies. + [..] + (@) Important note: Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to + select the RTC clock source; in this case the Backup domain will be reset in + order to modify the RTC Clock source, as consequence RTC registers (including + the backup registers) and RCC_BDCR register are set to their reset values. + +@endverbatim + * @{ + */ + +#if defined(STM32F446xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + uint32_t plli2sp = 0U; + uint32_t plli2sq = 0U; + uint32_t plli2sr = 0U; + uint32_t pllsaip = 0U; + uint32_t pllsaiq = 0U; + uint32_t plli2sused = 0U; + uint32_t pllsaiused = 0U; + + /* Check the peripheral clock selection parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*------------------------ I2S APB1 configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- I2S APB2 configuration ----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*--------------------------- SAI1 configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*-------------------------- SAI2 configuration ----------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); + + /* Configure SAI2 Clock source */ + __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); + + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- RTC configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + /* Configure Timer Prescaler */ + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- FMPI2C1 Configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ CEC Configuration -------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) + { + /* Check the parameters */ + assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); + + /* Configure the CEC clock source */ + __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- CLK48 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the CLK48 clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + + /* Enable the PLLSAI when it's used as clock source for CLK48 */ + if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- SDIO Configuration -------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ SPDIFRX Configuration ---------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) + { + /* Check the parameters */ + assert_param(IS_RCC_SPDIFRXCLKSOURCE(PeriphClkInit->SpdifClockSelection)); + + /* Configure the SPDIFRX clock source */ + __HAL_RCC_SPDIFRX_CONFIG(PeriphClkInit->SpdifClockSelection); + /* Enable the PLLI2S when it's used as clock source for SPDIFRX */ + if(PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- PLLI2S Configuration ------------------------*/ + /* PLLI2S is configured when a peripheral will use it as source clock : SAI1, SAI2, I2S on APB1, + I2S on APB2 or SPDIFRX */ + if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) + { + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* check for common PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /*------ In Case of PLLI2S is selected as source clock for I2S -----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S))) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Read PLLI2SP/PLLI2SQ value from PLLI2SCFGR register (this value is not needed for I2S configuration) */ + plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) + { + /* Check for PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + /* Check for PLLI2S/DIVQ parameters */ + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SP/PLLI2SR value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ + plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, PeriphClkInit->PLLI2S.PLLI2SQ, plli2sr); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*------ In Case of PLLI2S is selected as source clock for SPDIFRX -------*/ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) && (PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + plli2sq = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, plli2sq, plli2sr); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- PLLSAI Configuration -----------------------*/ + /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, CLK48 or SDIO */ + if(pllsaiused == 1U) + { + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIM_VALUE(PeriphClkInit->PLLSAI.PLLSAIM)); + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /*------ In Case of PLLSAI is selected as source clock for SAI -----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) + { + /* check for PLLSAIQ Parameter */ + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + /* check for PLLSAI/DIVQ Parameter */ + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, 0U); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*------ In Case of PLLSAI is selected as source clock for CLK48 ---------*/ + /* In Case of PLLI2S is selected as source clock for CLK48 */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); + /* Read PLLSAIQ value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Configure the PLLSAI division factors */ + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLI2SN/PLLSAIM) */ + /* 48CLK = f(PLLSAI clock output) = f(VCO clock) / PLLSAIP */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, 0U); + } + + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_SAI1 | RCC_PERIPHCLK_SAI2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_FMPI2C1 |\ + RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO |\ + RCC_PERIPHCLK_SPDIFRX; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SP = (uint32_t)((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Get the PLLSAI Clock configuration --------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIM = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM) >> RCC_PLLSAICFGR_PLLSAIM_Pos); + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIP = (uint32_t)((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + + /* Get the SAI1 clock configuration ----------------------------------------*/ + PeriphClkInit->Sai1ClockSelection = __HAL_RCC_GET_SAI1_SOURCE(); + + /* Get the SAI2 clock configuration ----------------------------------------*/ + PeriphClkInit->Sai2ClockSelection = __HAL_RCC_GET_SAI2_SOURCE(); + + /* Get the I2S APB1 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); + + /* Get the I2S APB2 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); + + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the CEC clock configuration -----------------------------------------*/ + PeriphClkInit->CecClockSelection = __HAL_RCC_GET_CEC_SOURCE(); + + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the CLK48 clock configuration ----------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + /* Get the SPDIFRX clock configuration -------------------------------------*/ + PeriphClkInit->SpdifClockSelection = __HAL_RCC_GET_SPDIFRX_SOURCE(); + + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_SAI1: SAI1 peripheral clock + * @arg RCC_PERIPHCLK_SAI2: SAI2 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + uint32_t tmpreg1 = 0U; + /* This variable used to store the SAI clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + /* This variable used to store the SAI clock source */ + uint32_t saiclocksource = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_SAI1: + case RCC_PERIPHCLK_SAI2: + { + saiclocksource = RCC->DCKCFGR; + saiclocksource &= (RCC_DCKCFGR_SAI1SRC | RCC_DCKCFGR_SAI2SRC); + switch (saiclocksource) + { + case 0U: /* PLLSAI is the clock source for SAI*/ + { + /* Configure the PLLSAI division factor */ + /* PLLSAI_VCO Input = PLL_SOURCE/PLLSAIM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM))); + } + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + tmpreg1 = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; + frequency = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U))/(tmpreg1); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + tmpreg1 = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); + frequency = frequency/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC_0: /* PLLI2S is the clock source for SAI*/ + case RCC_DCKCFGR_SAI2SRC_0: /* PLLI2S is the clock source for SAI*/ + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM))); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + tmpreg1 = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; + frequency = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U))/(tmpreg1); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + tmpreg1 = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); + frequency = frequency/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC_1: /* PLLR is the clock source for SAI*/ + case RCC_DCKCFGR_SAI2SRC_1: /* PLLR is the clock source for SAI*/ + { + /* Configure the PLLI2S division factor */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + /* SAI_CLK_x = PLL_VCO Output/PLLR */ + tmpreg1 = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; + frequency = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U))/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC: /* External clock is the clock source for SAI*/ + { + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + case RCC_DCKCFGR_SAI2SRC: /* PLLSRC(HSE or HSI) is the clock source for SAI*/ + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + frequency = (uint32_t)(HSI_VALUE); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + frequency = (uint32_t)(HSE_VALUE); + } + break; + } + default : + { + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB1: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB1CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB2: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB2CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC, RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + uint32_t pllsaip = 0U; + uint32_t pllsaiq = 0U; + uint32_t pllsair = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*--------------------------- CLK48 Configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the CLK48 clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ SDIO Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ + /*------------------- Common configuration SAI/I2S -------------------------*/ + /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------- I2S configuration -------------------------------*/ + /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added + only for I2S configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) + { + /* Check the PLLI2S division factors */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Configure the PLLI2S multiplication and division factors */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ + /*----------------------- Common configuration SAI/LTDC --------------------*/ + /* In Case of SAI, LTDC or CLK48 Clock Configuration through PLLSAI, PLLSAIN division + factor is common parameters for these peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && + (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP))) + { + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) + { + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, pllsair); + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*---------------------------- LTDC configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) + { + assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); + assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, pllsaiq, PeriphClkInit->PLLSAI.PLLSAIR); + /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); + } + + /*---------------------------- CLK48 configuration ------------------------*/ + /* Configure the PLLSAI when it is used as clock source for CLK48 */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == (RCC_PERIPHCLK_CLK48)) && + (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) + { + assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); + + /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* CLK48_CLK(first level) = PLLSAI_VCO Output/PLLSAIP */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, pllsair); + } + + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + + /*--------------------------------------------------------------------------*/ + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + return HAL_OK; +} + +/** + * @brief Configures the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI |\ + RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Get the PLLSAI Clock configuration --------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the CLK48 clock configuration -------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; +#if defined(STM32F413xx) || defined(STM32F423xx) + uint32_t plli2sq = 0U; +#endif /* STM32F413xx || STM32F423xx */ + uint32_t plli2sused = 0U; + + /* Check the peripheral clock selection parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*----------------------------------- I2S APB1 configuration ---------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------------- I2S APB2 configuration ---------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*----------------------- SAI1 Block A configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == (RCC_PERIPHCLK_SAIA)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAIACLKSOURCE(PeriphClkInit->SaiAClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(PeriphClkInit->SaiAClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLR) + { + /* Check for PLL/DIVR parameters */ + assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ + __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------- SAI1 Block B configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == (RCC_PERIPHCLK_SAIB)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAIBCLKSOURCE(PeriphClkInit->SaiBClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(PeriphClkInit->SaiBClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLR) + { + /* Check for PLL/DIVR parameters */ + assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ + __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); + } + } + /*--------------------------------------------------------------------------*/ +#endif /* STM32F413xx || STM32F423xx */ + + /*------------------------------------ RTC configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------ TIM configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + /* Configure Timer Prescaler */ + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- FMPI2C1 Configuration --------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- CLK48 Configuration ----------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + + /* Enable the PLLI2S when it's used as clock source for CLK48 */ + if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- SDIO Configuration -----------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------------------------- PLLI2S Configuration --------------*/ + /* PLLI2S is configured when a peripheral will use it as source clock : I2S on APB1 or + I2S on APB2*/ + if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) + { + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* check for common PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SCLKSOURCE(PeriphClkInit->PLLI2SSelection)); + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + /*-------------------- Set the PLL I2S clock -----------------------------*/ + __HAL_RCC_PLL_I2S_CONFIG(PeriphClkInit->PLLI2SSelection); + + /*------- In Case of PLLI2S is selected as source clock for I2S ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) && (PeriphClkInit->SdioClockSelection == RCC_SDIOCLKSOURCE_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ))) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == RCC_PERIPHCLK_SAIA) && (PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == RCC_PERIPHCLK_SAIB) && (PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR))) + { + /* Check for PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Check for PLLI2S/DIVR parameters */ + assert_param(IS_RCC_PLLI2S_DIVR_VALUE(PeriphClkInit->PLLI2SDivR)); + + /* Read PLLI2SQ value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ + plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLI2SDivR); + } +#endif /* STM32F413xx || STM32F423xx */ + + /*----------------- In Case of PLLI2S is just selected ------------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM1 clock source configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); + + /* Configure the DFSDM1 interface clock source */ + __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM1 Audio clock source configuration -------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); + + /* Configure the DFSDM1 Audio interface clock source */ + __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); + } + /*--------------------------------------------------------------------------*/ + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*-------------------- DFSDM2 clock source configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2) == RCC_PERIPHCLK_DFSDM2) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM2CLKSOURCE(PeriphClkInit->Dfsdm2ClockSelection)); + + /* Configure the DFSDM1 interface clock source */ + __HAL_RCC_DFSDM2_CONFIG(PeriphClkInit->Dfsdm2ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM2 Audio clock source configuration -------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2_AUDIO) == RCC_PERIPHCLK_DFSDM2_AUDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM2AUDIOCLKSOURCE(PeriphClkInit->Dfsdm2AudioClockSelection)); + + /* Configure the DFSDM1 Audio interface clock source */ + __HAL_RCC_DFSDM2AUDIO_CONFIG(PeriphClkInit->Dfsdm2AudioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- LPTIM1 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) + { + /* Check the parameters */ + assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); + + /* Configure the LPTIM1 clock source */ + __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); + } + /*--------------------------------------------------------------------------*/ +#endif /* STM32F413xx || STM32F423xx */ + + return HAL_OK; +} + +/** + * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ +#if defined(STM32F413xx) || defined(STM32F423xx) + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ + RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ + RCC_PERIPHCLK_DFSDM1_AUDIO | RCC_PERIPHCLK_DFSDM2 |\ + RCC_PERIPHCLK_DFSDM2_AUDIO | RCC_PERIPHCLK_LPTIM1 |\ + RCC_PERIPHCLK_SAIA | RCC_PERIPHCLK_SAIB; +#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ + RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ + RCC_PERIPHCLK_DFSDM1_AUDIO; +#endif /* STM32F413xx || STM32F423xx */ + + + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); +#if defined(STM32F413xx) || defined(STM32F423xx) + /* Get the PLL/PLLI2S division factors -------------------------------------*/ + PeriphClkInit->PLLI2SDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) >> RCC_DCKCFGR_PLLI2SDIVR_Pos); + PeriphClkInit->PLLDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> RCC_DCKCFGR_PLLDIVR_Pos); +#endif /* STM32F413xx || STM32F423xx */ + + /* Get the I2S APB1 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); + + /* Get the I2S APB2 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); + + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the CLK48 clock configuration ---------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + /* Get the DFSDM1 clock configuration --------------------------------------*/ + PeriphClkInit->Dfsdm1ClockSelection = __HAL_RCC_GET_DFSDM1_SOURCE(); + + /* Get the DFSDM1 Audio clock configuration --------------------------------*/ + PeriphClkInit->Dfsdm1AudioClockSelection = __HAL_RCC_GET_DFSDM1AUDIO_SOURCE(); + +#if defined(STM32F413xx) || defined(STM32F423xx) + /* Get the DFSDM2 clock configuration --------------------------------------*/ + PeriphClkInit->Dfsdm2ClockSelection = __HAL_RCC_GET_DFSDM2_SOURCE(); + + /* Get the DFSDM2 Audio clock configuration --------------------------------*/ + PeriphClkInit->Dfsdm2AudioClockSelection = __HAL_RCC_GET_DFSDM2AUDIO_SOURCE(); + + /* Get the LPTIM1 clock configuration --------------------------------------*/ + PeriphClkInit->Lptim1ClockSelection = __HAL_RCC_GET_LPTIM1_SOURCE(); + + /* Get the SAI1 Block Aclock configuration ---------------------------------*/ + PeriphClkInit->SaiAClockSelection = __HAL_RCC_GET_SAI_BLOCKA_SOURCE(); + + /* Get the SAI1 Block B clock configuration --------------------------------*/ + PeriphClkInit->SaiBClockSelection = __HAL_RCC_GET_SAI_BLOCKB_SOURCE(); +#endif /* STM32F413xx || STM32F423xx */ + + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(I2S..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S_APB1: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLI2S: + { + if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + } + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB1CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB2: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLI2S: + { + if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + } + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB2CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the + * RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). + * + * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case + * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup + * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- FMPI2C1 Configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- LPTIM1 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) + { + /* Check the parameters */ + assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); + + /* Configure the LPTIM1 clock source */ + __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); + } + + /*---------------------------- I2S Configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPBCLKSOURCE(PeriphClkInit->I2SClockSelection)); + + /* Configure the I2S clock source */ + __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2SClockSelection); + } + + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_LPTIM1 | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; + + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the I2S clock configuration -----------------------------------------*/ + PeriphClkInit->I2SClockSelection = __HAL_RCC_GET_I2S_SOURCE(); + + +} +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPBCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPBCLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPBCLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ + /*----------------------- Common configuration SAI/I2S ---------------------*/ + /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- I2S configuration -------------------------*/ + /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added + only for I2S configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) + { + /* Check the PLLI2S division factors */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Configure the PLLI2S multiplication and division factors */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ + /*----------------------- Common configuration SAI/LTDC --------------------*/ + /* In Case of SAI or LTDC Clock Configuration through PLLSAI, PLLSAIN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC)) + { + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) + { + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIQ, tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*---------------------------- LTDC configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) + { + assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); + assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); + + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg1, PeriphClkInit->PLLSAI.PLLSAIR); + /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); + } + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + return HAL_OK; +} + +/** + * @brief Configures the PeriphClkInit according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI | RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; + + /* Get the PLLI2S Clock configuration -----------------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Get the PLLSAI Clock configuration -----------------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors -----------------------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); + /* Get the RTC Clock configuration -----------------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the + * RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). + * + * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case + * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup + * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*---------------------------- I2S configuration ---------------------------*/ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); +#if defined(STM32F411xE) + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); +#endif /* STM32F411xE */ + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + +#if defined(STM32F411xE) + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SR); +#else + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); +#endif /* STM32F411xE */ + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_RTC; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); +#if defined(STM32F411xE) + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM); +#endif /* STM32F411xE */ + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { +#if defined(STM32F411xE) + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } +#else + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } +#endif /* STM32F411xE */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Select LSE mode + * + * @note This mode is only available for STM32F410xx/STM32F411xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. + * + * @param Mode specifies the LSE mode. + * This parameter can be one of the following values: + * @arg RCC_LSE_LOWPOWER_MODE: LSE oscillator in low power mode selection + * @arg RCC_LSE_HIGHDRIVE_MODE: LSE oscillator in High Drive mode selection + * @retval None + */ +void HAL_RCCEx_SelectLSEMode(uint8_t Mode) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE_MODE(Mode)); + if(Mode == RCC_LSE_HIGHDRIVE_MODE) + { + SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); + } + else + { + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); + } +} + +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +/** @defgroup RCCEx_Exported_Functions_Group2 Extended Clock management functions + * @brief Extended Clock management functions + * +@verbatim + =============================================================================== + ##### Extended clock management functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the + activation or deactivation of PLLI2S, PLLSAI. +@endverbatim + * @{ + */ + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Enable PLLI2S. + * @param PLLI2SInit pointer to an RCC_PLLI2SInitTypeDef structure that + * contains the configuration information for the PLLI2S + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit) +{ + uint32_t tickstart; + + /* Check for parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SInit->PLLI2SN)); + assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SInit->PLLI2SR)); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + assert_param(IS_RCC_PLLI2SM_VALUE(PLLI2SInit->PLLI2SM)); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ +#if defined(RCC_PLLI2SCFGR_PLLI2SP) + assert_param(IS_RCC_PLLI2SP_VALUE(PLLI2SInit->PLLI2SP)); +#endif /* RCC_PLLI2SCFGR_PLLI2SP */ +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) + assert_param(IS_RCC_PLLI2SQ_VALUE(PLLI2SInit->PLLI2SQ)); +#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + + /* Wait till PLLI2S is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Configure the PLLI2S division factors */ +#if defined(STM32F446xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SPCLK = PLLI2S_VCO / PLLI2SP */ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ + PLLI2SInit->PLLI2SP, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ + PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * PLLI2SN */ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F411xE) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); +#else + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x PLLI2SN */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); +#endif /* STM32F446xx */ + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + + /* Wait till PLLI2S is ready */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Disable PLLI2S. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void) +{ + uint32_t tickstart; + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + + /* Wait till PLLI2S is disabled */ + tickstart = HAL_GetTick(); + while(READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Enable PLLSAI. + * @param PLLSAIInit pointer to an RCC_PLLSAIInitTypeDef structure that + * contains the configuration information for the PLLSAI + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit) +{ + uint32_t tickstart; + + /* Check for parameters */ + assert_param(IS_RCC_PLLSAIN_VALUE(PLLSAIInit->PLLSAIN)); + assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIInit->PLLSAIQ)); +#if defined(RCC_PLLSAICFGR_PLLSAIM) + assert_param(IS_RCC_PLLSAIM_VALUE(PLLSAIInit->PLLSAIM)); +#endif /* RCC_PLLSAICFGR_PLLSAIM */ +#if defined(RCC_PLLSAICFGR_PLLSAIP) + assert_param(IS_RCC_PLLSAIP_VALUE(PLLSAIInit->PLLSAIP)); +#endif /* RCC_PLLSAICFGR_PLLSAIP */ +#if defined(RCC_PLLSAICFGR_PLLSAIR) + assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIInit->PLLSAIR)); +#endif /* RCC_PLLSAICFGR_PLLSAIR */ + + /* Disable the PLLSAI */ + __HAL_RCC_PLLSAI_DISABLE(); + + /* Wait till PLLSAI is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Configure the PLLSAI division factors */ +#if defined(STM32F446xx) + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLSAIN/PLLSAIM) */ + /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIM, PLLSAIInit->PLLSAIN, \ + PLLSAIInit->PLLSAIP, PLLSAIInit->PLLSAIQ, 0U); +#elif defined(STM32F469xx) || defined(STM32F479xx) + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * PLLSAIN */ + /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIP, \ + PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); +#else + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) x PLLSAIN */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); +#endif /* STM32F446xx */ + + /* Enable the PLLSAI */ + __HAL_RCC_PLLSAI_ENABLE(); + + /* Wait till PLLSAI is ready */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Disable PLLSAI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void) +{ + uint32_t tickstart; + + /* Disable the PLLSAI */ + __HAL_RCC_PLLSAI_DISABLE(); + + /* Wait till PLLSAI is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @} + */ + +#if defined(STM32F446xx) +/** + * @brief Returns the SYSCLK frequency + * + * @note This function implementation is valid only for STM32F446xx devices. + * @note This function add the PLL/PLLR System clock source + * + * @note The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) + * @note If SYSCLK source is PLL or PLLR, function returns values based on HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * + * @note Each time SYSCLK changes, this function must be called to update the + * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * + * @retval SYSCLK frequency + */ +uint32_t HAL_RCC_GetSysClockFreq(void) +{ + uint32_t pllm = 0U; + uint32_t pllvco = 0U; + uint32_t pllp = 0U; + uint32_t pllr = 0U; + uint32_t sysclockfreq = 0U; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ + { + sysclockfreq = HSI_VALUE; + break; + } + case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ + { + sysclockfreq = HSE_VALUE; + break; + } + case RCC_CFGR_SWS_PLL: /* PLL/PLLP used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLP */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); + + sysclockfreq = pllvco/pllp; + break; + } + case RCC_CFGR_SWS_PLLR: /* PLL/PLLR used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLR */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllr = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); + + sysclockfreq = pllvco/pllr; + break; + } + default: + { + sysclockfreq = HSI_VALUE; + break; + } + } + return sysclockfreq; +} +#endif /* STM32F446xx */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE, PLL, PLLI2S and PLLSAI OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO1 and MCO2 OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCC_DeInit(void) +{ + uint32_t tickstart; + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Set HSION bit to the reset value */ + SET_BIT(RCC->CR, RCC_CR_HSION); + + /* Wait till HSI is ready */ + while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET) + { + if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Set HSITRIM[4:0] bits to the reset value */ + SET_BIT(RCC->CR, RCC_CR_HSITRIM_4); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset CFGR register */ + CLEAR_REG(RCC->CFGR); + + /* Wait till clock switch is ready */ + while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RESET) + { + if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Clear HSEON, HSEBYP and CSSON bits */ + CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON); + + /* Wait till HSE is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Clear PLLON bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLON); + + /* Wait till PLL is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + +#if defined(RCC_PLLI2S_SUPPORT) + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset PLLI2SON bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); + + /* Wait till PLLI2S is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset PLLSAI bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); + + /* Wait till PLLSAI is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } +#endif /* RCC_PLLSAI_SUPPORT */ + + /* Once PLL, PLLI2S and PLLSAI are OFF, reset PLLCFGR register to default value */ +#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ + defined(STM32F423xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLR_1; +#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) + RCC->PLLCFGR = RCC_PLLCFGR_PLLR_0 | RCC_PLLCFGR_PLLR_1 | RCC_PLLCFGR_PLLR_2 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_0 | RCC_PLLCFGR_PLLQ_1 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLQ_3; +#else + RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2; +#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx || STM32F469xx || STM32F479xx */ + + /* Reset PLLI2SCFGR register to default value */ +#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ + defined(STM32F423xx) || defined(STM32F446xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F411xE) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; +#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx */ + + /* Reset PLLSAICFGR register */ +#if defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIR_1; +#elif defined(STM32F446xx) + RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2; +#endif /* STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F469xx || STM32F479xx */ + + /* Disable all interrupts */ + CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); + +#if defined(RCC_CIR_PLLI2SRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); +#endif /* RCC_CIR_PLLI2SRDYIE */ + +#if defined(RCC_CIR_PLLSAIRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); +#endif /* RCC_CIR_PLLSAIRDYIE */ + + /* Clear all interrupt flags */ + SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); + +#if defined(RCC_CIR_PLLI2SRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); +#endif /* RCC_CIR_PLLI2SRDYC */ + +#if defined(RCC_CIR_PLLSAIRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); +#endif /* RCC_CIR_PLLSAIRDYC */ + + /* Clear LSION bit */ + CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); + + /* Reset all CSR flags */ + SET_BIT(RCC->CSR, RCC_CSR_RMVF); + + /* Update the SystemCoreClock global variable */ + SystemCoreClock = HSI_VALUE; + + /* Adapt Systick interrupt period */ + if(HAL_InitTick(uwTickPrio) != HAL_OK) + { + return HAL_ERROR; + } + else + { + return HAL_OK; + } +} + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Initializes the RCC Oscillators according to the specified parameters in the + * RCC_OscInitTypeDef. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC Oscillators. + * @note The PLL is not disabled when used as system clock. + * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not + * supported by this API. User should request a transition to LSE Off + * first and then LSE On or LSE Bypass. + * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not + * supported by this API. User should request a transition to HSE Off + * first and then HSE On or HSE Bypass. + * @note This function add the PLL/PLLR factor management during PLL configuration this feature + * is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + uint32_t tickstart, pll_config; + + /* Check Null pointer */ + if(RCC_OscInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); + /*------------------------------- HSE Configuration ------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) + { + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); + /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ +#if defined(STM32F446xx) + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) +#else + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) +#endif /* STM32F446xx */ + { + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + { + return HAL_ERROR; + } + } + else + { + /* Set the new HSE configuration ---------------------------------------*/ + __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); + + /* Check the HSE State */ + if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSE is bypassed or disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*----------------------------- HSI Configuration --------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) + { + /* Check the parameters */ + assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); + assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); + + /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ +#if defined(STM32F446xx) + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI)) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) +#else + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) +#endif /* STM32F446xx */ + { + /* When HSI is used as system clock it will not disabled */ + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) + { + return HAL_ERROR; + } + /* Otherwise, just the calibration is allowed */ + else + { + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + } + else + { + /* Check the HSI State */ + if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) + { + /* Enable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + else + { + /* Disable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*------------------------------ LSI Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) + { + /* Check the parameters */ + assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); + + /* Check the LSI State */ + if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) + { + /* Enable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + /*------------------------------ LSE Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) + { + FlagStatus pwrclkchanged = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); + + /* Update LSE configuration in Backup Domain control register */ + /* Requires to enable write access to Backup Domain of necessary */ + if(__HAL_RCC_PWR_IS_CLK_DISABLED()) + { + __HAL_RCC_PWR_CLK_ENABLE(); + pwrclkchanged = SET; + } + + if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + /* Enable write access to Backup domain */ + SET_BIT(PWR->CR, PWR_CR_DBP); + + /* Wait for Backup domain Write protection disable */ + tickstart = HAL_GetTick(); + + while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Set the new LSE configuration -----------------------------------------*/ + __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); + /* Check the LSE State */ + if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Restore clock configuration if changed */ + if(pwrclkchanged == SET) + { + __HAL_RCC_PWR_CLK_DISABLE(); + } + } + /*-------------------------------- PLL Configuration -----------------------*/ + /* Check the parameters */ + assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); + if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) + { + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) + { + /* Check the parameters */ + assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); + assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); + assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); + assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); + assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); + assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); + + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Configure the main PLL clock source, multiplication and division factors. */ + WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ + RCC_OscInitStruct->PLL.PLLM | \ + (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ + (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ + (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos) | \ + (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))); + /* Enable the main PLL. */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + else + { + /* Check if there is a request to disable the PLL used as System clock source */ + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) + { + return HAL_ERROR; + } + else + { + /* Do not return HAL_ERROR if request repeats the current configuration */ + pll_config = RCC->PLLCFGR; +#if defined (RCC_PLLCFGR_PLLR) + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) +#else + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) +#endif + { + return HAL_ERROR; + } + } + } + } + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that will be configured. + * + * @note This function is only available in case of STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. + * @note This function add the PLL/PLLR factor management + * @retval None + */ +void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + /* Set all possible values for the Oscillator type parameter ---------------*/ + RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; + + /* Get the HSE configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) + { + RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; + } + else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) + { + RCC_OscInitStruct->HSEState = RCC_HSE_ON; + } + else + { + RCC_OscInitStruct->HSEState = RCC_HSE_OFF; + } + + /* Get the HSI configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) + { + RCC_OscInitStruct->HSIState = RCC_HSI_ON; + } + else + { + RCC_OscInitStruct->HSIState = RCC_HSI_OFF; + } + + RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); + + /* Get the LSE configuration -----------------------------------------------*/ + if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) + { + RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; + } + else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) + { + RCC_OscInitStruct->LSEState = RCC_LSE_ON; + } + else + { + RCC_OscInitStruct->LSEState = RCC_LSE_OFF; + } + + /* Get the LSI configuration -----------------------------------------------*/ + if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) + { + RCC_OscInitStruct->LSIState = RCC_LSI_ON; + } + else + { + RCC_OscInitStruct->LSIState = RCC_LSI_OFF; + } + + /* Get the PLL configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; + } + else + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; + } + RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); + RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); + RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); + RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); + RCC_OscInitStruct->PLL.PLLR = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); +} +#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#endif /* HAL_RCC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c index 62d5d65..9ca8257 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c @@ -1,3915 +1,3915 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spi.c - * @author MCD Application Team - * @brief SPI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Serial Peripheral Interface (SPI) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The SPI HAL driver can be used as follows: - - (#) Declare a SPI_HandleTypeDef handle structure, for example: - SPI_HandleTypeDef hspi; - - (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API: - (##) Enable the SPIx interface clock - (##) SPI pins configuration - (+++) Enable the clock for the SPI GPIOs - (+++) Configure these SPI pins as alternate function push-pull - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the SPIx interrupt priority - (+++) Enable the NVIC SPI IRQ handle - (##) DMA Configuration if you need to use DMA process - (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel - (+++) Enable the DMAx clock - (+++) Configure the DMA handle parameters - (+++) Configure the DMA Tx or Rx Stream/Channel - (+++) Associate the initialized hdma_tx(or _rx) handle to the hspi DMA Tx or Rx handle - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel - - (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS - management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure. - - (#) Initialize the SPI registers by calling the HAL_SPI_Init() API: - (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_SPI_MspInit() API. - [..] - Circular mode restriction: - (#) The DMA circular mode cannot be used when the SPI is configured in these modes: - (##) Master 2Lines RxOnly - (##) Master 1Line Rx - (#) The CRC feature is not managed when the DMA circular mode is enabled - (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs - the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks - [..] - Master Receive mode restriction: - (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=1) or - bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI - does not initiate a new transfer the following procedure has to be respected: - (##) HAL_SPI_DeInit() - (##) HAL_SPI_Init() - [..] - Callback registration: - - (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1U - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback. - - Function HAL_SPI_RegisterCallback() allows to register following callbacks: - (++) TxCpltCallback : SPI Tx Completed callback - (++) RxCpltCallback : SPI Rx Completed callback - (++) TxRxCpltCallback : SPI TxRx Completed callback - (++) TxHalfCpltCallback : SPI Tx Half Completed callback - (++) RxHalfCpltCallback : SPI Rx Half Completed callback - (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback - (++) ErrorCallback : SPI Error callback - (++) AbortCpltCallback : SPI Abort callback - (++) MspInitCallback : SPI Msp Init callback - (++) MspDeInitCallback : SPI Msp DeInit callback - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - - (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default - weak function. - HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (++) TxCpltCallback : SPI Tx Completed callback - (++) RxCpltCallback : SPI Rx Completed callback - (++) TxRxCpltCallback : SPI TxRx Completed callback - (++) TxHalfCpltCallback : SPI Tx Half Completed callback - (++) RxHalfCpltCallback : SPI Rx Half Completed callback - (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback - (++) ErrorCallback : SPI Error callback - (++) AbortCpltCallback : SPI Abort callback - (++) MspInitCallback : SPI Msp Init callback - (++) MspDeInitCallback : SPI Msp DeInit callback - - [..] - By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - - [..] - Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit() - or HAL_SPI_Init() function. - - [..] - When the compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - [..] - Using the HAL it is not possible to reach all supported SPI frequency with the different SPI Modes, - the following table resume the max SPI frequency reached with data size 8bits/16bits, - according to frequency of the APBx Peripheral Clock (fPCLK) used by the SPI instance. - - @endverbatim - - Additional table : - - DataSize = SPI_DATASIZE_8BIT: - +----------------------------------------------------------------------------------------------+ - | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | - | Process | Transfer mode |---------------------|----------------------|----------------------| - | | | Master | Slave | Master | Slave | Master | Slave | - |==============================================================================================| - | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | / | Interrupt | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA | - | R |----------------|----------|----------|-----------|----------|-----------|----------| - | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | R | Interrupt | Fpclk/8 | Fpclk/8 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| - +----------------------------------------------------------------------------------------------+ - - DataSize = SPI_DATASIZE_16BIT: - +----------------------------------------------------------------------------------------------+ - | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | - | Process | Transfer mode |---------------------|----------------------|----------------------| - | | | Master | Slave | Master | Slave | Master | Slave | - |==============================================================================================| - | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | / | Interrupt | Fpclk/4 | Fpclk/4 | NA | NA | NA | NA | - | R |----------------|----------|----------|-----------|----------|-----------|----------| - | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/32 | Fpclk/2 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | R | Interrupt | Fpclk/4 | Fpclk/4 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/32 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | T | Interrupt | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/64 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| - +----------------------------------------------------------------------------------------------+ - @note The max SPI frequency depend on SPI data size (8bits, 16bits), - SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA). - @note - (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA() - (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA() - (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA() - - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SPI SPI - * @brief SPI HAL module driver - * @{ - */ -#ifdef HAL_SPI_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup SPI_Private_Constants SPI Private Constants - * @{ - */ -#define SPI_DEFAULT_TIMEOUT 100U -#define SPI_BSY_FLAG_WORKAROUND_TIMEOUT 1000U /*!< Timeout 1000 µs */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup SPI_Private_Functions SPI Private Functions - * @{ - */ -static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAError(DMA_HandleTypeDef *hdma); -static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, - uint32_t Timeout, uint32_t Tickstart); -static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -#if (USE_SPI_CRC != 0U) -static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); -#endif /* USE_SPI_CRC */ -static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi); -static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SPI_Exported_Functions SPI Exported Functions - * @{ - */ - -/** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - de-initialize the SPIx peripheral: - - (+) User must implement HAL_SPI_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_SPI_Init() to configure the selected device with - the selected configuration: - (++) Mode - (++) Direction - (++) Data Size - (++) Clock Polarity and Phase - (++) NSS Management - (++) BaudRate Prescaler - (++) FirstBit - (++) TIMode - (++) CRC Calculation - (++) CRC Polynomial if CRC enabled - - (+) Call the function HAL_SPI_DeInit() to restore the default configuration - of the selected SPIx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the SPI according to the specified parameters - * in the SPI_InitTypeDef and initialize the associated handle. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi) -{ - /* Check the SPI handle allocation */ - if (hspi == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); - assert_param(IS_SPI_MODE(hspi->Init.Mode)); - assert_param(IS_SPI_DIRECTION(hspi->Init.Direction)); - assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize)); - assert_param(IS_SPI_NSS(hspi->Init.NSS)); - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit)); - assert_param(IS_SPI_TIMODE(hspi->Init.TIMode)); - if (hspi->Init.TIMode == SPI_TIMODE_DISABLE) - { - assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity)); - assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase)); - - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - } - else - { - /* Baudrate prescaler not use in Motoraola Slave mode. force to default value */ - hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; - } - } - else - { - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - - /* Force polarity and phase to TI protocaol requirements */ - hspi->Init.CLKPolarity = SPI_POLARITY_LOW; - hspi->Init.CLKPhase = SPI_PHASE_1EDGE; - } -#if (USE_SPI_CRC != 0U) - assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation)); - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial)); - } -#else - hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; -#endif /* USE_SPI_CRC */ - - if (hspi->State == HAL_SPI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hspi->Lock = HAL_UNLOCKED; - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - /* Init the SPI Callback settings */ - hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ - hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ - hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - - if (hspi->MspInitCallback == NULL) - { - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - hspi->MspInitCallback(hspi); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - HAL_SPI_MspInit(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - - hspi->State = HAL_SPI_STATE_BUSY; - - /* Disable the selected SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - - /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/ - /* Configure : SPI Mode, Communication Mode, Data size, Clock polarity and phase, NSS management, - Communication speed, First bit and CRC calculation state */ - WRITE_REG(hspi->Instance->CR1, ((hspi->Init.Mode & (SPI_CR1_MSTR | SPI_CR1_SSI)) | - (hspi->Init.Direction & (SPI_CR1_RXONLY | SPI_CR1_BIDIMODE)) | - (hspi->Init.DataSize & SPI_CR1_DFF) | - (hspi->Init.CLKPolarity & SPI_CR1_CPOL) | - (hspi->Init.CLKPhase & SPI_CR1_CPHA) | - (hspi->Init.NSS & SPI_CR1_SSM) | - (hspi->Init.BaudRatePrescaler & SPI_CR1_BR_Msk) | - (hspi->Init.FirstBit & SPI_CR1_LSBFIRST) | - (hspi->Init.CRCCalculation & SPI_CR1_CRCEN))); - - /* Configure : NSS management, TI Mode */ - WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | (hspi->Init.TIMode & SPI_CR2_FRF))); - -#if (USE_SPI_CRC != 0U) - /*---------------------------- SPIx CRCPOLY Configuration ------------------*/ - /* Configure : CRC Polynomial */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - WRITE_REG(hspi->Instance->CRCPR, (hspi->Init.CRCPolynomial & SPI_CRCPR_CRCPOLY_Msk)); - } -#endif /* USE_SPI_CRC */ - -#if defined(SPI_I2SCFGR_I2SMOD) - /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */ - CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD); -#endif /* SPI_I2SCFGR_I2SMOD */ - - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->State = HAL_SPI_STATE_READY; - - return HAL_OK; -} - -/** - * @brief De-Initialize the SPI peripheral. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi) -{ - /* Check the SPI handle allocation */ - if (hspi == NULL) - { - return HAL_ERROR; - } - - /* Check SPI Instance parameter */ - assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); - - hspi->State = HAL_SPI_STATE_BUSY; - - /* Disable the SPI Peripheral Clock */ - __HAL_SPI_DISABLE(hspi); - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - if (hspi->MspDeInitCallback == NULL) - { - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - hspi->MspDeInitCallback(hspi); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - HAL_SPI_MspDeInit(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->State = HAL_SPI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Initialize the SPI MSP. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_MspInit should be implemented in the user file - */ -} - -/** - * @brief De-Initialize the SPI MSP. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_MspDeInit should be implemented in the user file - */ -} - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User SPI Callback - * To be used instead of the weak predefined callback - * @param hspi Pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI. - * @param CallbackID ID of the callback to be registered - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, - pSPI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hspi->ErrorCode |= HAL_SPI_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hspi); - - if (HAL_SPI_STATE_READY == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_TX_COMPLETE_CB_ID : - hspi->TxCpltCallback = pCallback; - break; - - case HAL_SPI_RX_COMPLETE_CB_ID : - hspi->RxCpltCallback = pCallback; - break; - - case HAL_SPI_TX_RX_COMPLETE_CB_ID : - hspi->TxRxCpltCallback = pCallback; - break; - - case HAL_SPI_TX_HALF_COMPLETE_CB_ID : - hspi->TxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_RX_HALF_COMPLETE_CB_ID : - hspi->RxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : - hspi->TxRxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_ERROR_CB_ID : - hspi->ErrorCallback = pCallback; - break; - - case HAL_SPI_ABORT_CB_ID : - hspi->AbortCpltCallback = pCallback; - break; - - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = pCallback; - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SPI_STATE_RESET == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = pCallback; - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspi); - return status; -} - -/** - * @brief Unregister an SPI Callback - * SPI callback is redirected to the weak predefined callback - * @param hspi Pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI. - * @param CallbackID ID of the callback to be unregistered - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hspi); - - if (HAL_SPI_STATE_READY == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_TX_COMPLETE_CB_ID : - hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_SPI_RX_COMPLETE_CB_ID : - hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_SPI_TX_RX_COMPLETE_CB_ID : - hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - break; - - case HAL_SPI_TX_HALF_COMPLETE_CB_ID : - hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_SPI_RX_HALF_COMPLETE_CB_ID : - hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : - hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ - break; - - case HAL_SPI_ERROR_CB_ID : - hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_SPI_ABORT_CB_ID : - hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SPI_STATE_RESET == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspi); - return status; -} -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPI_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SPI - data transfers. - - [..] The SPI supports master and slave mode : - - (#) There are two modes of transfer: - (++) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode: The communication is performed using Interrupts - or DMA, These APIs return the HAL status. - The end of the data processing will be indicated through the - dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks - will be executed respectively at the end of the transmit or Receive process - The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected - - (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA) - exist for 1Line (simplex) and 2Lines (full duplex) modes. - -@endverbatim - * @{ - */ - -/** - * @brief Transmit an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - HAL_StatusTypeDef errorcode = HAL_OK; - uint16_t initial_TxXferCount; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - initial_TxXferCount = Size; - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - hspi->TxISR = NULL; - hspi->RxISR = NULL; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Transmit data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - /* Transmit data in 16 Bit mode */ - while (hspi->TxXferCount > 0U) - { - /* Wait until TXE flag is set to send data */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - /* Transmit data in 8 Bit mode */ - else - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - while (hspi->TxXferCount > 0U) - { - /* Wait until TXE flag is set to send data */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - errorcode = HAL_ERROR; - } - -error: - hspi->State = HAL_SPI_STATE_READY; - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - uint32_t tickstart; - HAL_StatusTypeDef errorcode = HAL_OK; - - if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->pTxBuffPtr = (uint8_t *)NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - /* this is done to handle the CRCNEXT before the latest data */ - hspi->RxXferCount--; - } -#endif /* USE_SPI_CRC */ - - /* Configure communication direction: 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Receive data in 8 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_8BIT) - { - /* Transfer loop */ - while (hspi->RxXferCount > 0U) - { - /* Check the RXNE flag */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) - { - /* read the received data */ - (* (uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint8_t); - hspi->RxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - else - { - /* Transfer loop */ - while (hspi->RxXferCount > 0U) - { - /* Check the RXNE flag */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - -#if (USE_SPI_CRC != 0U) - /* Handle the CRC Transmission */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* freeze the CRC before the latest data */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - - /* Read the latest data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - /* the latest data has not been received */ - errorcode = HAL_TIMEOUT; - goto error; - } - - /* Receive last data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - } - /* Receive last data in 8 Bit mode */ - else - { - (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; - } - - /* Wait the CRC data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - errorcode = HAL_TIMEOUT; - goto error; - } - - /* Read CRC to Flush DR and RXNE flag */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - errorcode = HAL_ERROR; - } - -error : - hspi->State = HAL_SPI_STATE_READY; - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @param Size amount of data to be sent and received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, - uint32_t Timeout) -{ - uint16_t initial_TxXferCount; - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Variable used to alternate Rx and Tx during transfer */ - uint32_t txallowed = 1U; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - initial_TxXferCount = Size; - - if (!((tmp_state == HAL_SPI_STATE_READY) || \ - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferCount = Size; - hspi->RxXferSize = Size; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferCount = Size; - hspi->TxXferSize = Size; - - /*Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Transmit and Receive data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) - { - /* Check TXE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - /* Next Data is a reception (Rx). Tx not allowed */ - txallowed = 0U; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - } - - /* Check RXNE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - /* Next Data is a Transmission (Tx). Tx is allowed */ - txallowed = 1U; - } - if (((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - /* Transmit and Receive data in 8 Bit mode */ - else - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) - { - /* Check TXE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) - { - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - /* Next Data is a reception (Rx). Tx not allowed */ - txallowed = 0U; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - } - - /* Wait until RXNE flag is reset */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) - { - (*(uint8_t *)hspi->pRxBuffPtr) = hspi->Instance->DR; - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - /* Next Data is a Transmission (Tx). Tx is allowed */ - txallowed = 1U; - } - if ((((HAL_GetTick() - tickstart) >= Timeout) && ((Timeout != HAL_MAX_DELAY))) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - -#if (USE_SPI_CRC != 0U) - /* Read CRC from DR to close CRC calculation process */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait until TXE flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - /* Error on the CRC reception */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - errorcode = HAL_TIMEOUT; - goto error; - } - /* Read CRC */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } - - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - /* Clear CRC Flag */ - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - - errorcode = HAL_ERROR; - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - errorcode = HAL_ERROR; - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - goto error; - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - -error : - hspi->State = HAL_SPI_STATE_READY; - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - hspi->RxISR = NULL; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->TxISR = SPI_TxISR_16BIT; - } - else - { - hspi->TxISR = SPI_TxISR_8BIT; - } - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); - - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pTxBuffPtr = (uint8_t *)NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - hspi->TxISR = NULL; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->RxISR = SPI_RxISR_16BIT; - } - else - { - hspi->RxISR = SPI_RxISR_8BIT; - } - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - /* Note : The SPI must be enabled after unlocking current process - to avoid the risk of SPI interrupt handle execution before current - process unlock */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @param Size amount of data to be sent and received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size) -{ - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process locked */ - __HAL_LOCK(hspi); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - - if (!((tmp_state == HAL_SPI_STATE_READY) || \ - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->RxISR = SPI_2linesRxISR_16BIT; - hspi->TxISR = SPI_2linesTxISR_16BIT; - } - else - { - hspi->RxISR = SPI_2linesRxISR_8BIT; - hspi->TxISR = SPI_2linesTxISR_8BIT; - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE, RXNE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with DMA. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check tx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->TxISR = NULL; - hspi->RxISR = NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Set the SPI TxDMA Half transfer complete callback */ - hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt; - - /* Set the SPI TxDMA transfer complete callback */ - hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt; - - /* Set the DMA error callback */ - hspi->hdmatx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmatx->XferAbortCallback = NULL; - - /* Enable the Tx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, - hspi->TxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Tx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in non-blocking mode with DMA. - * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @note When the CRC feature is enabled the pData Length must be Size + 1. - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check rx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); - - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - - /* Check tx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Set the SPI RxDMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; - - /* Set the SPI Rx DMA transfer complete callback */ - hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; - - /* Set the DMA error callback */ - hspi->hdmarx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Enable the Rx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, - hspi->RxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Rx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - -error: - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in non-blocking mode with DMA. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @note When the CRC feature is enabled the pRxData Length must be Size + 1 - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size) -{ - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check rx & tx dma handles */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process locked */ - __HAL_LOCK(hspi); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - - if (!((tmp_state == HAL_SPI_STATE_READY) || - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */ - if (hspi->State == HAL_SPI_STATE_BUSY_RX) - { - /* Set the SPI Rx DMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; - hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; - } - else - { - /* Set the SPI Tx/Rx DMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt; - hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt; - } - - /* Set the DMA error callback */ - hspi->hdmarx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Enable the Rx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, - hspi->RxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Enable Rx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - - /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing - is performed in DMA reception complete callback */ - hspi->hdmatx->XferHalfCpltCallback = NULL; - hspi->hdmatx->XferCpltCallback = NULL; - hspi->hdmatx->XferErrorCallback = NULL; - hspi->hdmatx->XferAbortCallback = NULL; - - /* Enable the Tx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, - hspi->TxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Tx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Abort ongoing transfer (blocking mode). - * @param hspi SPI handle. - * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), - * started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SPI Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode; - __IO uint32_t count; - __IO uint32_t resetcount; - - /* Initialized local variable */ - errorcode = HAL_OK; - resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - count = resetcount; - - /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); - - /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) - { - hspi->TxISR = SPI_AbortTx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) - { - hspi->RxISR = SPI_AbortRx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - /* Disable the SPI DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */ - if (hspi->hdmatx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ - hspi->hdmatx->XferAbortCallback = NULL; - - /* Abort DMA Tx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN)); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - } - } - - /* Disable the SPI DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */ - if (hspi->hdmarx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Abort DMA Rx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - - /* Disable peripheral */ - __HAL_SPI_DISABLE(hspi); - - /* Disable Rx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN)); - } - } - /* Reset Tx and Rx transfer counters */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check error during Abort procedure */ - if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) - { - /* return HAL_Error in case of error during Abort procedure */ - errorcode = HAL_ERROR; - } - else - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->state to ready */ - hspi->State = HAL_SPI_STATE_READY; - - return errorcode; -} - -/** - * @brief Abort ongoing transfer (Interrupt mode). - * @param hspi SPI handle. - * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), - * started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SPI Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode; - uint32_t abortcplt ; - __IO uint32_t count; - __IO uint32_t resetcount; - - /* Initialized local variable */ - errorcode = HAL_OK; - abortcplt = 1U; - resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - count = resetcount; - - /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); - - /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) - { - hspi->TxISR = SPI_AbortTx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) - { - hspi->RxISR = SPI_AbortRx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (hspi->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback; - } - else - { - hspi->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (hspi->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback; - } - else - { - hspi->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the SPI DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - /* Abort the SPI DMA Tx Stream/Channel */ - if (hspi->hdmatx != NULL) - { - /* Abort DMA Tx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK) - { - hspi->hdmatx->XferAbortCallback = NULL; - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - else - { - abortcplt = 0U; - } - } - } - /* Disable the SPI DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - /* Abort the SPI DMA Rx Stream/Channel */ - if (hspi->hdmarx != NULL) - { - /* Abort DMA Rx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK) - { - hspi->hdmarx->XferAbortCallback = NULL; - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - else - { - abortcplt = 0U; - } - } - } - - if (abortcplt == 1U) - { - /* Reset Tx and Rx transfer counters */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check error during Abort procedure */ - if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) - { - /* return HAL_Error in case of error during Abort procedure */ - errorcode = HAL_ERROR; - } - else - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - - return errorcode; -} - -/** - * @brief Pause the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi) -{ - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Disable the SPI DMA Tx & Rx requests */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Resume the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi) -{ - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Enable the SPI DMA Tx & Rx requests */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Stop the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - /* The Lock is not implemented on this API to allow the user application - to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback() - */ - - /* Abort the SPI DMA tx Stream/Channel */ - if (hspi->hdmatx != NULL) - { - if (HAL_OK != HAL_DMA_Abort(hspi->hdmatx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - /* Abort the SPI DMA rx Stream/Channel */ - if (hspi->hdmarx != NULL) - { - if (HAL_OK != HAL_DMA_Abort(hspi->hdmarx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - - /* Disable the SPI DMA Tx & Rx requests */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - hspi->State = HAL_SPI_STATE_READY; - return errorcode; -} - -/** - * @brief Handle SPI interrupt request. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval None - */ -void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi) -{ - uint32_t itsource = hspi->Instance->CR2; - uint32_t itflag = hspi->Instance->SR; - - /* SPI in mode Receiver ----------------------------------------------------*/ - if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) == RESET) && - (SPI_CHECK_FLAG(itflag, SPI_FLAG_RXNE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_RXNE) != RESET)) - { - hspi->RxISR(hspi); - return; - } - - /* SPI in mode Transmitter -------------------------------------------------*/ - if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_TXE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_TXE) != RESET)) - { - hspi->TxISR(hspi); - return; - } - - /* SPI in Error Treatment --------------------------------------------------*/ - if (((SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) || (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) - || (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_ERR) != RESET)) - { - /* SPI Overrun error interrupt occurred ----------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) - { - if (hspi->State != HAL_SPI_STATE_BUSY_TX) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR); - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - else - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - return; - } - } - - /* SPI Mode Fault error interrupt occurred -------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF); - __HAL_SPI_CLEAR_MODFFLAG(hspi); - } - - /* SPI Frame error interrupt occurred ------------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE); - __HAL_SPI_CLEAR_FREFLAG(hspi); - } - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Disable all interrupts */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR); - - hspi->State = HAL_SPI_STATE_READY; - /* Disable the SPI DMA requests if enabled */ - if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN))) - { - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); - - /* Abort the SPI DMA Rx channel */ - if (hspi->hdmarx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ - hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError; - if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmarx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - } - /* Abort the SPI DMA Tx channel */ - if (hspi->hdmatx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ - hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError; - if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmatx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - } - return; - } -} - -/** - * @brief Tx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_RxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Tx and Rx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxRxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxHalfCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file - */ -} - -/** - * @brief Tx and Rx Half Transfer callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file - */ -} - -/** - * @brief SPI error callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_ErrorCallback should be implemented in the user file - */ - /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes - and user can use HAL_SPI_GetError() API to check the latest error occurred - */ -} - -/** - * @brief SPI Abort Complete callback. - * @param hspi SPI handle. - * @retval None - */ -__weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief SPI control functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the SPI. - (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral - (+) HAL_SPI_GetError() check in run-time Errors occurring during communication -@endverbatim - * @{ - */ - -/** - * @brief Return the SPI handle state. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval SPI state - */ -HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi) -{ - /* Return SPI handle state */ - return hspi->State; -} - -/** - * @brief Return the SPI error code. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval SPI error code in bitmap format - */ -uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi) -{ - /* Return SPI ErrorCode */ - return hspi->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup SPI_Private_Functions - * @brief Private functions - * @{ - */ - -/** - * @brief DMA SPI transmit process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received data is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - hspi->TxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user Tx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxCpltCallback(hspi); -#else - HAL_SPI_TxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - -#if (USE_SPI_CRC != 0U) - /* CRC handling */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait until RXNE flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - /* Error on the CRC reception */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - } - /* Read CRC */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check if we are in Master RX 2 line mode */ - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - } - else - { - /* Normal case */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - } - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - - hspi->RxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI transmit receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - -#if (USE_SPI_CRC != 0U) - /* CRC handling */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait the CRC data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - } - /* Read CRC to Flush DR and RXNE flag */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Disable Rx/Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - hspi->TxXferCount = 0U; - hspi->RxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user TxRx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxCpltCallback(hspi); -#else - HAL_SPI_TxRxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half transmit process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Tx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxHalfCpltCallback(hspi); -#else - HAL_SPI_TxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half receive process complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Rx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxHalfCpltCallback(hspi); -#else - HAL_SPI_RxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half transmit receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user TxRx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxHalfCpltCallback(hspi); -#else - HAL_SPI_TxRxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI communication error callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAError(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Stop the disable DMA transfer on SPI side */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - hspi->State = HAL_SPI_STATE_READY; - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - __IO uint32_t count; - - hspi->hdmatx->XferAbortCallback = NULL; - count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Check if an Abort process is still ongoing */ - if (hspi->hdmarx != NULL) - { - if (hspi->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check no error during Abort procedure */ - if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - hspi->hdmarx->XferAbortCallback = NULL; - - /* Disable Rx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - - /* Check Busy flag */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - - /* Check if an Abort process is still ongoing */ - if (hspi->hdmatx != NULL) - { - if (hspi->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check no error during Abort procedure */ - if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Receive data in 8bit mode */ - *hspi->pRxBuffPtr = *((__IO uint8_t *)&hspi->Instance->DR); - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - - /* Check end of the reception */ - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_2linesRxISR_8BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint8_t *ptmpreg8; - __IO uint8_t tmpreg8 = 0; - - /* Initialize the 8bit temporary pointer */ - ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; - /* Read 8bit CRC to flush Data Register */ - tmpreg8 = *ptmpreg8; - /* To avoid GCC warning */ - UNUSED(tmpreg8); - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - - /* Check the end of the transmission */ - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Set CRC Next Bit to send CRC */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - - if (hspi->RxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -/** - * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Receive data in 16 Bit mode */ - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_2linesRxISR_16BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable RXNE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - - /* Read 16bit CRC to flush Data Register */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - /* Disable RXNE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); - - SPI_CloseRxTx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Transmit data in 16 Bit mode */ - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - - /* Enable CRC Transmission */ - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Set CRC Next Bit to send CRC */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - - if (hspi->RxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 8-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint8_t *ptmpreg8; - __IO uint8_t tmpreg8 = 0; - - /* Initialize the 8bit temporary pointer */ - ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; - /* Read 8bit CRC to flush Data Register */ - tmpreg8 = *ptmpreg8; - /* To avoid GCC warning */ - UNUSED(tmpreg8); - - SPI_CloseRx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Manage the receive 8-bit in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *hspi->pRxBuffPtr = (*(__IO uint8_t *)&hspi->Instance->DR); - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_RxISR_8BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - SPI_CloseRx_ISR(hspi); - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 16-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - - /* Read 16bit CRC to flush Data Register */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - SPI_CloseRx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Manage the 16-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_RxISR_16BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - SPI_CloseRx_ISR(hspi); - } -} - -/** - * @brief Handle the data 8-bit transmit in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Enable CRC Transmission */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - SPI_CloseTx_ISR(hspi); - } -} - -/** - * @brief Handle the data 16-bit transmit in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Transmit data in 16 Bit mode */ - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Enable CRC Transmission */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - SPI_CloseTx_ISR(hspi); - } -} - -/** - * @brief Handle SPI Communication Timeout. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param Flag SPI flag to check - * @param State flag state to check - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, - uint32_t Timeout, uint32_t Tickstart) -{ - __IO uint32_t count; - uint32_t tmp_timeout; - uint32_t tmp_tickstart; - - /* Adjust Timeout value in case of end of transfer */ - tmp_timeout = Timeout - (HAL_GetTick() - Tickstart); - tmp_tickstart = HAL_GetTick(); - - /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */ - count = tmp_timeout * ((SystemCoreClock * 32U) >> 20U); - - while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State) - { - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U)) - { - /* Disable the SPI and reset the CRC: the CRC value should be cleared - on both master and slave sides in order to resynchronize the master - and slave for their respective CRC calculation */ - - /* Disable TXE, RXNE and ERR interrupts for the interrupt process */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); - - if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) - || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) - { - /* Disable SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - } - - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } - - hspi->State = HAL_SPI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_TIMEOUT; - } - /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */ - if (count == 0U) - { - tmp_timeout = 0U; - } - count--; - } - } - - return HAL_OK; -} - -/** - * @brief Handle the check of the RX transaction complete. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) -{ - if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) - || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) - { - /* Disable SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - } - - /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - if (hspi->Init.Direction != SPI_DIRECTION_2LINES_RXONLY) - { - /* Control the BSY flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - else - { - /* Wait the RXNE reset */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - } - else - { - /* Wait the RXNE reset */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Handle the check of the RXTX or TX transaction complete. - * @param hspi SPI handle - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) -{ - /* Timeout in µs */ - __IO uint32_t count = SPI_BSY_FLAG_WORKAROUND_TIMEOUT * (SystemCoreClock / 24U / 1000000U); - /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - /* Control the BSY flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - else - { - /* Wait BSY flag during 1 Byte time transfer in case of Full-Duplex and Tx transfer - * If Timeout is reached, the transfer is considered as finish. - * User have to calculate the timeout value to fit with the time of 1 byte transfer. - * This time is directly link with the SPI clock from Master device. - */ - do - { - if (count == 0U) - { - break; - } - count--; - } while (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_BSY) != RESET); - } - - return HAL_OK; -} - -/** - * @brief Handle the end of the RXTX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi) -{ - uint32_t tickstart; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) - { - hspi->State = HAL_SPI_STATE_READY; - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { -#endif /* USE_SPI_CRC */ - if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) - { - if (hspi->State == HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxCpltCallback(hspi); -#else - HAL_SPI_TxRxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - } - else - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -#if (USE_SPI_CRC != 0U) - } -#endif /* USE_SPI_CRC */ -} - -/** - * @brief Handle the end of the RX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi) -{ - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { -#endif /* USE_SPI_CRC */ - if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) - { - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -#if (USE_SPI_CRC != 0U) - } -#endif /* USE_SPI_CRC */ -} - -/** - * @brief Handle the end of the TX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi) -{ - uint32_t tickstart; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Disable TXE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - hspi->State = HAL_SPI_STATE_READY; - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxCpltCallback(hspi); -#else - HAL_SPI_TxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Handle abort a Rx transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE)); - - /* Flush Data Register by a blank read */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - hspi->State = HAL_SPI_STATE_ABORT; -} - -/** - * @brief Handle abort a Tx or Rx/Tx transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi) -{ - /* Disable TXEIE interrupt */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE)); - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - hspi->State = HAL_SPI_STATE_ABORT; -} - -/** - * @} - */ - -#endif /* HAL_SPI_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_spi.c + * @author MCD Application Team + * @brief SPI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Serial Peripheral Interface (SPI) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The SPI HAL driver can be used as follows: + + (#) Declare a SPI_HandleTypeDef handle structure, for example: + SPI_HandleTypeDef hspi; + + (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API: + (##) Enable the SPIx interface clock + (##) SPI pins configuration + (+++) Enable the clock for the SPI GPIOs + (+++) Configure these SPI pins as alternate function push-pull + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the SPIx interrupt priority + (+++) Enable the NVIC SPI IRQ handle + (##) DMA Configuration if you need to use DMA process + (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel + (+++) Enable the DMAx clock + (+++) Configure the DMA handle parameters + (+++) Configure the DMA Tx or Rx Stream/Channel + (+++) Associate the initialized hdma_tx(or _rx) handle to the hspi DMA Tx or Rx handle + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel + + (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS + management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure. + + (#) Initialize the SPI registers by calling the HAL_SPI_Init() API: + (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_SPI_MspInit() API. + [..] + Circular mode restriction: + (#) The DMA circular mode cannot be used when the SPI is configured in these modes: + (##) Master 2Lines RxOnly + (##) Master 1Line Rx + (#) The CRC feature is not managed when the DMA circular mode is enabled + (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs + the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks + [..] + Master Receive mode restriction: + (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=1) or + bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI + does not initiate a new transfer the following procedure has to be respected: + (##) HAL_SPI_DeInit() + (##) HAL_SPI_Init() + [..] + Callback registration: + + (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1U + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback. + + Function HAL_SPI_RegisterCallback() allows to register following callbacks: + (++) TxCpltCallback : SPI Tx Completed callback + (++) RxCpltCallback : SPI Rx Completed callback + (++) TxRxCpltCallback : SPI TxRx Completed callback + (++) TxHalfCpltCallback : SPI Tx Half Completed callback + (++) RxHalfCpltCallback : SPI Rx Half Completed callback + (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback + (++) ErrorCallback : SPI Error callback + (++) AbortCpltCallback : SPI Abort callback + (++) MspInitCallback : SPI Msp Init callback + (++) MspDeInitCallback : SPI Msp DeInit callback + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + + (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default + weak function. + HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (++) TxCpltCallback : SPI Tx Completed callback + (++) RxCpltCallback : SPI Rx Completed callback + (++) TxRxCpltCallback : SPI TxRx Completed callback + (++) TxHalfCpltCallback : SPI Tx Half Completed callback + (++) RxHalfCpltCallback : SPI Rx Half Completed callback + (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback + (++) ErrorCallback : SPI Error callback + (++) AbortCpltCallback : SPI Abort callback + (++) MspInitCallback : SPI Msp Init callback + (++) MspDeInitCallback : SPI Msp DeInit callback + + [..] + By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + + [..] + Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit() + or HAL_SPI_Init() function. + + [..] + When the compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + [..] + Using the HAL it is not possible to reach all supported SPI frequency with the different SPI Modes, + the following table resume the max SPI frequency reached with data size 8bits/16bits, + according to frequency of the APBx Peripheral Clock (fPCLK) used by the SPI instance. + + @endverbatim + + Additional table : + + DataSize = SPI_DATASIZE_8BIT: + +----------------------------------------------------------------------------------------------+ + | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | + | Process | Transfer mode |---------------------|----------------------|----------------------| + | | | Master | Slave | Master | Slave | Master | Slave | + |==============================================================================================| + | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | / | Interrupt | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA | + | R |----------------|----------|----------|-----------|----------|-----------|----------| + | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | R | Interrupt | Fpclk/8 | Fpclk/8 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| + +----------------------------------------------------------------------------------------------+ + + DataSize = SPI_DATASIZE_16BIT: + +----------------------------------------------------------------------------------------------+ + | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | + | Process | Transfer mode |---------------------|----------------------|----------------------| + | | | Master | Slave | Master | Slave | Master | Slave | + |==============================================================================================| + | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | / | Interrupt | Fpclk/4 | Fpclk/4 | NA | NA | NA | NA | + | R |----------------|----------|----------|-----------|----------|-----------|----------| + | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/32 | Fpclk/2 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | R | Interrupt | Fpclk/4 | Fpclk/4 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/32 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | T | Interrupt | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/64 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| + +----------------------------------------------------------------------------------------------+ + @note The max SPI frequency depend on SPI data size (8bits, 16bits), + SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA). + @note + (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA() + (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA() + (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA() + + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SPI SPI + * @brief SPI HAL module driver + * @{ + */ +#ifdef HAL_SPI_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/** @defgroup SPI_Private_Constants SPI Private Constants + * @{ + */ +#define SPI_DEFAULT_TIMEOUT 100U +#define SPI_BSY_FLAG_WORKAROUND_TIMEOUT 1000U /*!< Timeout 1000 µs */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup SPI_Private_Functions SPI Private Functions + * @{ + */ +static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAError(DMA_HandleTypeDef *hdma); +static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, + uint32_t Timeout, uint32_t Tickstart); +static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +#if (USE_SPI_CRC != 0U) +static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); +#endif /* USE_SPI_CRC */ +static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi); +static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SPI_Exported_Functions SPI Exported Functions + * @{ + */ + +/** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + de-initialize the SPIx peripheral: + + (+) User must implement HAL_SPI_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_SPI_Init() to configure the selected device with + the selected configuration: + (++) Mode + (++) Direction + (++) Data Size + (++) Clock Polarity and Phase + (++) NSS Management + (++) BaudRate Prescaler + (++) FirstBit + (++) TIMode + (++) CRC Calculation + (++) CRC Polynomial if CRC enabled + + (+) Call the function HAL_SPI_DeInit() to restore the default configuration + of the selected SPIx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the SPI according to the specified parameters + * in the SPI_InitTypeDef and initialize the associated handle. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi) +{ + /* Check the SPI handle allocation */ + if (hspi == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); + assert_param(IS_SPI_MODE(hspi->Init.Mode)); + assert_param(IS_SPI_DIRECTION(hspi->Init.Direction)); + assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize)); + assert_param(IS_SPI_NSS(hspi->Init.NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit)); + assert_param(IS_SPI_TIMODE(hspi->Init.TIMode)); + if (hspi->Init.TIMode == SPI_TIMODE_DISABLE) + { + assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity)); + assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase)); + + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + } + else + { + /* Baudrate prescaler not use in Motoraola Slave mode. force to default value */ + hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; + } + } + else + { + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + + /* Force polarity and phase to TI protocaol requirements */ + hspi->Init.CLKPolarity = SPI_POLARITY_LOW; + hspi->Init.CLKPhase = SPI_PHASE_1EDGE; + } +#if (USE_SPI_CRC != 0U) + assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation)); + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial)); + } +#else + hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; +#endif /* USE_SPI_CRC */ + + if (hspi->State == HAL_SPI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hspi->Lock = HAL_UNLOCKED; + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + /* Init the SPI Callback settings */ + hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ + hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ + hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + + if (hspi->MspInitCallback == NULL) + { + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + hspi->MspInitCallback(hspi); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + HAL_SPI_MspInit(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + + hspi->State = HAL_SPI_STATE_BUSY; + + /* Disable the selected SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + + /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/ + /* Configure : SPI Mode, Communication Mode, Data size, Clock polarity and phase, NSS management, + Communication speed, First bit and CRC calculation state */ + WRITE_REG(hspi->Instance->CR1, ((hspi->Init.Mode & (SPI_CR1_MSTR | SPI_CR1_SSI)) | + (hspi->Init.Direction & (SPI_CR1_RXONLY | SPI_CR1_BIDIMODE)) | + (hspi->Init.DataSize & SPI_CR1_DFF) | + (hspi->Init.CLKPolarity & SPI_CR1_CPOL) | + (hspi->Init.CLKPhase & SPI_CR1_CPHA) | + (hspi->Init.NSS & SPI_CR1_SSM) | + (hspi->Init.BaudRatePrescaler & SPI_CR1_BR_Msk) | + (hspi->Init.FirstBit & SPI_CR1_LSBFIRST) | + (hspi->Init.CRCCalculation & SPI_CR1_CRCEN))); + + /* Configure : NSS management, TI Mode */ + WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | (hspi->Init.TIMode & SPI_CR2_FRF))); + +#if (USE_SPI_CRC != 0U) + /*---------------------------- SPIx CRCPOLY Configuration ------------------*/ + /* Configure : CRC Polynomial */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + WRITE_REG(hspi->Instance->CRCPR, (hspi->Init.CRCPolynomial & SPI_CRCPR_CRCPOLY_Msk)); + } +#endif /* USE_SPI_CRC */ + +#if defined(SPI_I2SCFGR_I2SMOD) + /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */ + CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD); +#endif /* SPI_I2SCFGR_I2SMOD */ + + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->State = HAL_SPI_STATE_READY; + + return HAL_OK; +} + +/** + * @brief De-Initialize the SPI peripheral. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi) +{ + /* Check the SPI handle allocation */ + if (hspi == NULL) + { + return HAL_ERROR; + } + + /* Check SPI Instance parameter */ + assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); + + hspi->State = HAL_SPI_STATE_BUSY; + + /* Disable the SPI Peripheral Clock */ + __HAL_SPI_DISABLE(hspi); + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + if (hspi->MspDeInitCallback == NULL) + { + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + hspi->MspDeInitCallback(hspi); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + HAL_SPI_MspDeInit(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->State = HAL_SPI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Initialize the SPI MSP. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_MspInit should be implemented in the user file + */ +} + +/** + * @brief De-Initialize the SPI MSP. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_MspDeInit should be implemented in the user file + */ +} + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User SPI Callback + * To be used instead of the weak predefined callback + * @param hspi Pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI. + * @param CallbackID ID of the callback to be registered + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, + pSPI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hspi->ErrorCode |= HAL_SPI_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hspi); + + if (HAL_SPI_STATE_READY == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_TX_COMPLETE_CB_ID : + hspi->TxCpltCallback = pCallback; + break; + + case HAL_SPI_RX_COMPLETE_CB_ID : + hspi->RxCpltCallback = pCallback; + break; + + case HAL_SPI_TX_RX_COMPLETE_CB_ID : + hspi->TxRxCpltCallback = pCallback; + break; + + case HAL_SPI_TX_HALF_COMPLETE_CB_ID : + hspi->TxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_RX_HALF_COMPLETE_CB_ID : + hspi->RxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : + hspi->TxRxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_ERROR_CB_ID : + hspi->ErrorCallback = pCallback; + break; + + case HAL_SPI_ABORT_CB_ID : + hspi->AbortCpltCallback = pCallback; + break; + + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = pCallback; + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SPI_STATE_RESET == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = pCallback; + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspi); + return status; +} + +/** + * @brief Unregister an SPI Callback + * SPI callback is redirected to the weak predefined callback + * @param hspi Pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI. + * @param CallbackID ID of the callback to be unregistered + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hspi); + + if (HAL_SPI_STATE_READY == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_TX_COMPLETE_CB_ID : + hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_SPI_RX_COMPLETE_CB_ID : + hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_SPI_TX_RX_COMPLETE_CB_ID : + hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + break; + + case HAL_SPI_TX_HALF_COMPLETE_CB_ID : + hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_SPI_RX_HALF_COMPLETE_CB_ID : + hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : + hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ + break; + + case HAL_SPI_ERROR_CB_ID : + hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_SPI_ABORT_CB_ID : + hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SPI_STATE_RESET == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspi); + return status; +} +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SPI + data transfers. + + [..] The SPI supports master and slave mode : + + (#) There are two modes of transfer: + (++) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode: The communication is performed using Interrupts + or DMA, These APIs return the HAL status. + The end of the data processing will be indicated through the + dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks + will be executed respectively at the end of the transmit or Receive process + The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected + + (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA) + exist for 1Line (simplex) and 2Lines (full duplex) modes. + +@endverbatim + * @{ + */ + +/** + * @brief Transmit an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + HAL_StatusTypeDef errorcode = HAL_OK; + uint16_t initial_TxXferCount; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + initial_TxXferCount = Size; + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + hspi->TxISR = NULL; + hspi->RxISR = NULL; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Transmit data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + /* Transmit data in 16 Bit mode */ + while (hspi->TxXferCount > 0U) + { + /* Wait until TXE flag is set to send data */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + /* Transmit data in 8 Bit mode */ + else + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + while (hspi->TxXferCount > 0U) + { + /* Wait until TXE flag is set to send data */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + errorcode = HAL_ERROR; + } + +error: + hspi->State = HAL_SPI_STATE_READY; + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + uint32_t tickstart; + HAL_StatusTypeDef errorcode = HAL_OK; + + if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->pTxBuffPtr = (uint8_t *)NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + /* this is done to handle the CRCNEXT before the latest data */ + hspi->RxXferCount--; + } +#endif /* USE_SPI_CRC */ + + /* Configure communication direction: 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Receive data in 8 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_8BIT) + { + /* Transfer loop */ + while (hspi->RxXferCount > 0U) + { + /* Check the RXNE flag */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) + { + /* read the received data */ + (* (uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint8_t); + hspi->RxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + else + { + /* Transfer loop */ + while (hspi->RxXferCount > 0U) + { + /* Check the RXNE flag */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + +#if (USE_SPI_CRC != 0U) + /* Handle the CRC Transmission */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* freeze the CRC before the latest data */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + + /* Read the latest data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + /* the latest data has not been received */ + errorcode = HAL_TIMEOUT; + goto error; + } + + /* Receive last data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + } + /* Receive last data in 8 Bit mode */ + else + { + (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; + } + + /* Wait the CRC data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + errorcode = HAL_TIMEOUT; + goto error; + } + + /* Read CRC to Flush DR and RXNE flag */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + errorcode = HAL_ERROR; + } + +error : + hspi->State = HAL_SPI_STATE_READY; + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @param Size amount of data to be sent and received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, + uint32_t Timeout) +{ + uint16_t initial_TxXferCount; + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Variable used to alternate Rx and Tx during transfer */ + uint32_t txallowed = 1U; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + initial_TxXferCount = Size; + + if (!((tmp_state == HAL_SPI_STATE_READY) || \ + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferCount = Size; + hspi->RxXferSize = Size; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferCount = Size; + hspi->TxXferSize = Size; + + /*Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Transmit and Receive data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) + { + /* Check TXE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + /* Next Data is a reception (Rx). Tx not allowed */ + txallowed = 0U; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + } + + /* Check RXNE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + /* Next Data is a Transmission (Tx). Tx is allowed */ + txallowed = 1U; + } + if (((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + /* Transmit and Receive data in 8 Bit mode */ + else + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) + { + /* Check TXE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) + { + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + /* Next Data is a reception (Rx). Tx not allowed */ + txallowed = 0U; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + } + + /* Wait until RXNE flag is reset */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) + { + (*(uint8_t *)hspi->pRxBuffPtr) = hspi->Instance->DR; + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + /* Next Data is a Transmission (Tx). Tx is allowed */ + txallowed = 1U; + } + if ((((HAL_GetTick() - tickstart) >= Timeout) && ((Timeout != HAL_MAX_DELAY))) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + +#if (USE_SPI_CRC != 0U) + /* Read CRC from DR to close CRC calculation process */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait until TXE flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + /* Error on the CRC reception */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + errorcode = HAL_TIMEOUT; + goto error; + } + /* Read CRC */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } + + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + /* Clear CRC Flag */ + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + + errorcode = HAL_ERROR; + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + errorcode = HAL_ERROR; + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + goto error; + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + +error : + hspi->State = HAL_SPI_STATE_READY; + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + hspi->RxISR = NULL; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->TxISR = SPI_TxISR_16BIT; + } + else + { + hspi->TxISR = SPI_TxISR_8BIT; + } + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); + + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pTxBuffPtr = (uint8_t *)NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + hspi->TxISR = NULL; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->RxISR = SPI_RxISR_16BIT; + } + else + { + hspi->RxISR = SPI_RxISR_8BIT; + } + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + /* Note : The SPI must be enabled after unlocking current process + to avoid the risk of SPI interrupt handle execution before current + process unlock */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @param Size amount of data to be sent and received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size) +{ + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process locked */ + __HAL_LOCK(hspi); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + + if (!((tmp_state == HAL_SPI_STATE_READY) || \ + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->RxISR = SPI_2linesRxISR_16BIT; + hspi->TxISR = SPI_2linesTxISR_16BIT; + } + else + { + hspi->RxISR = SPI_2linesRxISR_8BIT; + hspi->TxISR = SPI_2linesTxISR_8BIT; + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE, RXNE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with DMA. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check tx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->TxISR = NULL; + hspi->RxISR = NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Set the SPI TxDMA Half transfer complete callback */ + hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt; + + /* Set the SPI TxDMA transfer complete callback */ + hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt; + + /* Set the DMA error callback */ + hspi->hdmatx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmatx->XferAbortCallback = NULL; + + /* Enable the Tx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, + hspi->TxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Tx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in non-blocking mode with DMA. + * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @note When the CRC feature is enabled the pData Length must be Size + 1. + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check rx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); + + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + + /* Check tx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Set the SPI RxDMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; + + /* Set the SPI Rx DMA transfer complete callback */ + hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; + + /* Set the DMA error callback */ + hspi->hdmarx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Enable the Rx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, + hspi->RxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Rx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + +error: + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in non-blocking mode with DMA. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @note When the CRC feature is enabled the pRxData Length must be Size + 1 + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size) +{ + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check rx & tx dma handles */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process locked */ + __HAL_LOCK(hspi); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + + if (!((tmp_state == HAL_SPI_STATE_READY) || + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */ + if (hspi->State == HAL_SPI_STATE_BUSY_RX) + { + /* Set the SPI Rx DMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; + hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; + } + else + { + /* Set the SPI Tx/Rx DMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt; + hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt; + } + + /* Set the DMA error callback */ + hspi->hdmarx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Enable the Rx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, + hspi->RxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Enable Rx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + + /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing + is performed in DMA reception complete callback */ + hspi->hdmatx->XferHalfCpltCallback = NULL; + hspi->hdmatx->XferCpltCallback = NULL; + hspi->hdmatx->XferErrorCallback = NULL; + hspi->hdmatx->XferAbortCallback = NULL; + + /* Enable the Tx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, + hspi->TxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Tx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Abort ongoing transfer (blocking mode). + * @param hspi SPI handle. + * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), + * started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SPI Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode; + __IO uint32_t count; + __IO uint32_t resetcount; + + /* Initialized local variable */ + errorcode = HAL_OK; + resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + count = resetcount; + + /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); + + /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) + { + hspi->TxISR = SPI_AbortTx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) + { + hspi->RxISR = SPI_AbortRx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + /* Disable the SPI DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */ + if (hspi->hdmatx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ + hspi->hdmatx->XferAbortCallback = NULL; + + /* Abort DMA Tx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN)); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + } + } + + /* Disable the SPI DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */ + if (hspi->hdmarx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Abort DMA Rx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + + /* Disable peripheral */ + __HAL_SPI_DISABLE(hspi); + + /* Disable Rx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN)); + } + } + /* Reset Tx and Rx transfer counters */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check error during Abort procedure */ + if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) + { + /* return HAL_Error in case of error during Abort procedure */ + errorcode = HAL_ERROR; + } + else + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->state to ready */ + hspi->State = HAL_SPI_STATE_READY; + + return errorcode; +} + +/** + * @brief Abort ongoing transfer (Interrupt mode). + * @param hspi SPI handle. + * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), + * started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SPI Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode; + uint32_t abortcplt ; + __IO uint32_t count; + __IO uint32_t resetcount; + + /* Initialized local variable */ + errorcode = HAL_OK; + abortcplt = 1U; + resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + count = resetcount; + + /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); + + /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) + { + hspi->TxISR = SPI_AbortTx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) + { + hspi->RxISR = SPI_AbortRx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (hspi->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback; + } + else + { + hspi->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (hspi->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback; + } + else + { + hspi->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the SPI DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + /* Abort the SPI DMA Tx Stream/Channel */ + if (hspi->hdmatx != NULL) + { + /* Abort DMA Tx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK) + { + hspi->hdmatx->XferAbortCallback = NULL; + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + else + { + abortcplt = 0U; + } + } + } + /* Disable the SPI DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + /* Abort the SPI DMA Rx Stream/Channel */ + if (hspi->hdmarx != NULL) + { + /* Abort DMA Rx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK) + { + hspi->hdmarx->XferAbortCallback = NULL; + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + else + { + abortcplt = 0U; + } + } + } + + if (abortcplt == 1U) + { + /* Reset Tx and Rx transfer counters */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check error during Abort procedure */ + if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) + { + /* return HAL_Error in case of error during Abort procedure */ + errorcode = HAL_ERROR; + } + else + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + + return errorcode; +} + +/** + * @brief Pause the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi) +{ + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Disable the SPI DMA Tx & Rx requests */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Resume the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi) +{ + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Enable the SPI DMA Tx & Rx requests */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Stop the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + /* The Lock is not implemented on this API to allow the user application + to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback() + */ + + /* Abort the SPI DMA tx Stream/Channel */ + if (hspi->hdmatx != NULL) + { + if (HAL_OK != HAL_DMA_Abort(hspi->hdmatx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + /* Abort the SPI DMA rx Stream/Channel */ + if (hspi->hdmarx != NULL) + { + if (HAL_OK != HAL_DMA_Abort(hspi->hdmarx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + + /* Disable the SPI DMA Tx & Rx requests */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + hspi->State = HAL_SPI_STATE_READY; + return errorcode; +} + +/** + * @brief Handle SPI interrupt request. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval None + */ +void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi) +{ + uint32_t itsource = hspi->Instance->CR2; + uint32_t itflag = hspi->Instance->SR; + + /* SPI in mode Receiver ----------------------------------------------------*/ + if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) == RESET) && + (SPI_CHECK_FLAG(itflag, SPI_FLAG_RXNE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_RXNE) != RESET)) + { + hspi->RxISR(hspi); + return; + } + + /* SPI in mode Transmitter -------------------------------------------------*/ + if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_TXE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_TXE) != RESET)) + { + hspi->TxISR(hspi); + return; + } + + /* SPI in Error Treatment --------------------------------------------------*/ + if (((SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) || (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) + || (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_ERR) != RESET)) + { + /* SPI Overrun error interrupt occurred ----------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) + { + if (hspi->State != HAL_SPI_STATE_BUSY_TX) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR); + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + else + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + return; + } + } + + /* SPI Mode Fault error interrupt occurred -------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF); + __HAL_SPI_CLEAR_MODFFLAG(hspi); + } + + /* SPI Frame error interrupt occurred ------------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE); + __HAL_SPI_CLEAR_FREFLAG(hspi); + } + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Disable all interrupts */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR); + + hspi->State = HAL_SPI_STATE_READY; + /* Disable the SPI DMA requests if enabled */ + if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN))) + { + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); + + /* Abort the SPI DMA Rx channel */ + if (hspi->hdmarx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ + hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError; + if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmarx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + } + /* Abort the SPI DMA Tx channel */ + if (hspi->hdmatx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ + hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError; + if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmatx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + } + return; + } +} + +/** + * @brief Tx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_RxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Tx and Rx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxRxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxHalfCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file + */ +} + +/** + * @brief Tx and Rx Half Transfer callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file + */ +} + +/** + * @brief SPI error callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_ErrorCallback should be implemented in the user file + */ + /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes + and user can use HAL_SPI_GetError() API to check the latest error occurred + */ +} + +/** + * @brief SPI Abort Complete callback. + * @param hspi SPI handle. + * @retval None + */ +__weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief SPI control functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the SPI. + (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral + (+) HAL_SPI_GetError() check in run-time Errors occurring during communication +@endverbatim + * @{ + */ + +/** + * @brief Return the SPI handle state. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval SPI state + */ +HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi) +{ + /* Return SPI handle state */ + return hspi->State; +} + +/** + * @brief Return the SPI error code. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval SPI error code in bitmap format + */ +uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi) +{ + /* Return SPI ErrorCode */ + return hspi->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup SPI_Private_Functions + * @brief Private functions + * @{ + */ + +/** + * @brief DMA SPI transmit process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received data is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + hspi->TxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user Tx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxCpltCallback(hspi); +#else + HAL_SPI_TxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + +#if (USE_SPI_CRC != 0U) + /* CRC handling */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait until RXNE flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + /* Error on the CRC reception */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + } + /* Read CRC */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check if we are in Master RX 2 line mode */ + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + } + else + { + /* Normal case */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + } + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + + hspi->RxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI transmit receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + +#if (USE_SPI_CRC != 0U) + /* CRC handling */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait the CRC data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + } + /* Read CRC to Flush DR and RXNE flag */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Disable Rx/Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + hspi->TxXferCount = 0U; + hspi->RxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user TxRx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxCpltCallback(hspi); +#else + HAL_SPI_TxRxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half transmit process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Tx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxHalfCpltCallback(hspi); +#else + HAL_SPI_TxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half receive process complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Rx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxHalfCpltCallback(hspi); +#else + HAL_SPI_RxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half transmit receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user TxRx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxHalfCpltCallback(hspi); +#else + HAL_SPI_TxRxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI communication error callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAError(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Stop the disable DMA transfer on SPI side */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + hspi->State = HAL_SPI_STATE_READY; + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + __IO uint32_t count; + + hspi->hdmatx->XferAbortCallback = NULL; + count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Check if an Abort process is still ongoing */ + if (hspi->hdmarx != NULL) + { + if (hspi->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check no error during Abort procedure */ + if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + hspi->hdmarx->XferAbortCallback = NULL; + + /* Disable Rx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + + /* Check Busy flag */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + + /* Check if an Abort process is still ongoing */ + if (hspi->hdmatx != NULL) + { + if (hspi->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check no error during Abort procedure */ + if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Receive data in 8bit mode */ + *hspi->pRxBuffPtr = *((__IO uint8_t *)&hspi->Instance->DR); + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + + /* Check end of the reception */ + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_2linesRxISR_8BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint8_t *ptmpreg8; + __IO uint8_t tmpreg8 = 0; + + /* Initialize the 8bit temporary pointer */ + ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; + /* Read 8bit CRC to flush Data Register */ + tmpreg8 = *ptmpreg8; + /* To avoid GCC warning */ + UNUSED(tmpreg8); + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + + /* Check the end of the transmission */ + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Set CRC Next Bit to send CRC */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + + if (hspi->RxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +/** + * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Receive data in 16 Bit mode */ + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_2linesRxISR_16BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable RXNE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + + /* Read 16bit CRC to flush Data Register */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + /* Disable RXNE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); + + SPI_CloseRxTx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Transmit data in 16 Bit mode */ + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + + /* Enable CRC Transmission */ + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Set CRC Next Bit to send CRC */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + + if (hspi->RxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 8-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint8_t *ptmpreg8; + __IO uint8_t tmpreg8 = 0; + + /* Initialize the 8bit temporary pointer */ + ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; + /* Read 8bit CRC to flush Data Register */ + tmpreg8 = *ptmpreg8; + /* To avoid GCC warning */ + UNUSED(tmpreg8); + + SPI_CloseRx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Manage the receive 8-bit in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *hspi->pRxBuffPtr = (*(__IO uint8_t *)&hspi->Instance->DR); + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_RxISR_8BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + SPI_CloseRx_ISR(hspi); + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 16-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + + /* Read 16bit CRC to flush Data Register */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + SPI_CloseRx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Manage the 16-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_RxISR_16BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + SPI_CloseRx_ISR(hspi); + } +} + +/** + * @brief Handle the data 8-bit transmit in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Enable CRC Transmission */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + SPI_CloseTx_ISR(hspi); + } +} + +/** + * @brief Handle the data 16-bit transmit in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Transmit data in 16 Bit mode */ + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Enable CRC Transmission */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + SPI_CloseTx_ISR(hspi); + } +} + +/** + * @brief Handle SPI Communication Timeout. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param Flag SPI flag to check + * @param State flag state to check + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, + uint32_t Timeout, uint32_t Tickstart) +{ + __IO uint32_t count; + uint32_t tmp_timeout; + uint32_t tmp_tickstart; + + /* Adjust Timeout value in case of end of transfer */ + tmp_timeout = Timeout - (HAL_GetTick() - Tickstart); + tmp_tickstart = HAL_GetTick(); + + /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */ + count = tmp_timeout * ((SystemCoreClock * 32U) >> 20U); + + while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State) + { + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U)) + { + /* Disable the SPI and reset the CRC: the CRC value should be cleared + on both master and slave sides in order to resynchronize the master + and slave for their respective CRC calculation */ + + /* Disable TXE, RXNE and ERR interrupts for the interrupt process */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); + + if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) + || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) + { + /* Disable SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + } + + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } + + hspi->State = HAL_SPI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_TIMEOUT; + } + /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */ + if (count == 0U) + { + tmp_timeout = 0U; + } + count--; + } + } + + return HAL_OK; +} + +/** + * @brief Handle the check of the RX transaction complete. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) +{ + if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) + || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) + { + /* Disable SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + } + + /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + if (hspi->Init.Direction != SPI_DIRECTION_2LINES_RXONLY) + { + /* Control the BSY flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + else + { + /* Wait the RXNE reset */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + } + else + { + /* Wait the RXNE reset */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Handle the check of the RXTX or TX transaction complete. + * @param hspi SPI handle + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) +{ + /* Timeout in µs */ + __IO uint32_t count = SPI_BSY_FLAG_WORKAROUND_TIMEOUT * (SystemCoreClock / 24U / 1000000U); + /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + /* Control the BSY flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + else + { + /* Wait BSY flag during 1 Byte time transfer in case of Full-Duplex and Tx transfer + * If Timeout is reached, the transfer is considered as finish. + * User have to calculate the timeout value to fit with the time of 1 byte transfer. + * This time is directly link with the SPI clock from Master device. + */ + do + { + if (count == 0U) + { + break; + } + count--; + } while (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_BSY) != RESET); + } + + return HAL_OK; +} + +/** + * @brief Handle the end of the RXTX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi) +{ + uint32_t tickstart; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) + { + hspi->State = HAL_SPI_STATE_READY; + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { +#endif /* USE_SPI_CRC */ + if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) + { + if (hspi->State == HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxCpltCallback(hspi); +#else + HAL_SPI_TxRxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + } + else + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +#if (USE_SPI_CRC != 0U) + } +#endif /* USE_SPI_CRC */ +} + +/** + * @brief Handle the end of the RX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi) +{ + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { +#endif /* USE_SPI_CRC */ + if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) + { + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +#if (USE_SPI_CRC != 0U) + } +#endif /* USE_SPI_CRC */ +} + +/** + * @brief Handle the end of the TX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi) +{ + uint32_t tickstart; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Disable TXE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + hspi->State = HAL_SPI_STATE_READY; + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxCpltCallback(hspi); +#else + HAL_SPI_TxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Handle abort a Rx transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE)); + + /* Flush Data Register by a blank read */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + hspi->State = HAL_SPI_STATE_ABORT; +} + +/** + * @brief Handle abort a Tx or Rx/Tx transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi) +{ + /* Disable TXEIE interrupt */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE)); + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + hspi->State = HAL_SPI_STATE_ABORT; +} + +/** + * @} + */ + +#endif /* HAL_SPI_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c index 1ca1781..eb3f5c3 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c @@ -1,7621 +1,7621 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim.c - * @author MCD Application Team - * @brief TIM HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Timer (TIM) peripheral: - * + TIM Time Base Initialization - * + TIM Time Base Start - * + TIM Time Base Start Interruption - * + TIM Time Base Start DMA - * + TIM Output Compare/PWM Initialization - * + TIM Output Compare/PWM Channel Configuration - * + TIM Output Compare/PWM Start - * + TIM Output Compare/PWM Start Interruption - * + TIM Output Compare/PWM Start DMA - * + TIM Input Capture Initialization - * + TIM Input Capture Channel Configuration - * + TIM Input Capture Start - * + TIM Input Capture Start Interruption - * + TIM Input Capture Start DMA - * + TIM One Pulse Initialization - * + TIM One Pulse Channel Configuration - * + TIM One Pulse Start - * + TIM Encoder Interface Initialization - * + TIM Encoder Interface Start - * + TIM Encoder Interface Start Interruption - * + TIM Encoder Interface Start DMA - * + Commutation Event configuration with Interruption and DMA - * + TIM OCRef clear configuration - * + TIM External Clock configuration - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### TIMER Generic features ##### - ============================================================================== - [..] The Timer features include: - (#) 16-bit up, down, up/down auto-reload counter. - (#) 16-bit programmable prescaler allowing dividing (also on the fly) the - counter clock frequency either by any factor between 1 and 65536. - (#) Up to 4 independent channels for: - (++) Input Capture - (++) Output Compare - (++) PWM generation (Edge and Center-aligned Mode) - (++) One-pulse mode output - (#) Synchronization circuit to control the timer with external signals and to interconnect - several timers together. - (#) Supports incremental encoder for positioning purposes - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the TIM low level resources by implementing the following functions - depending on the selected feature: - (++) Time Base : HAL_TIM_Base_MspInit() - (++) Input Capture : HAL_TIM_IC_MspInit() - (++) Output Compare : HAL_TIM_OC_MspInit() - (++) PWM generation : HAL_TIM_PWM_MspInit() - (++) One-pulse mode output : HAL_TIM_OnePulse_MspInit() - (++) Encoder mode output : HAL_TIM_Encoder_MspInit() - - (#) Initialize the TIM low level resources : - (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); - (##) TIM pins configuration - (+++) Enable the clock for the TIM GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); - - (#) The external Clock can be configured, if needed (the default clock is the - internal clock from the APBx), using the following function: - HAL_TIM_ConfigClockSource, the clock configuration should be done before - any start function. - - (#) Configure the TIM in the desired functioning mode using one of the - Initialization function of this driver: - (++) HAL_TIM_Base_Init: to use the Timer to generate a simple time base - (++) HAL_TIM_OC_Init and HAL_TIM_OC_ConfigChannel: to use the Timer to generate an - Output Compare signal. - (++) HAL_TIM_PWM_Init and HAL_TIM_PWM_ConfigChannel: to use the Timer to generate a - PWM signal. - (++) HAL_TIM_IC_Init and HAL_TIM_IC_ConfigChannel: to use the Timer to measure an - external signal. - (++) HAL_TIM_OnePulse_Init and HAL_TIM_OnePulse_ConfigChannel: to use the Timer - in One Pulse Mode. - (++) HAL_TIM_Encoder_Init: to use the Timer Encoder Interface. - - (#) Activate the TIM peripheral using one of the start functions depending from the feature used: - (++) Time Base : HAL_TIM_Base_Start(), HAL_TIM_Base_Start_DMA(), HAL_TIM_Base_Start_IT() - (++) Input Capture : HAL_TIM_IC_Start(), HAL_TIM_IC_Start_DMA(), HAL_TIM_IC_Start_IT() - (++) Output Compare : HAL_TIM_OC_Start(), HAL_TIM_OC_Start_DMA(), HAL_TIM_OC_Start_IT() - (++) PWM generation : HAL_TIM_PWM_Start(), HAL_TIM_PWM_Start_DMA(), HAL_TIM_PWM_Start_IT() - (++) One-pulse mode output : HAL_TIM_OnePulse_Start(), HAL_TIM_OnePulse_Start_IT() - (++) Encoder mode output : HAL_TIM_Encoder_Start(), HAL_TIM_Encoder_Start_DMA(), HAL_TIM_Encoder_Start_IT(). - - (#) The DMA Burst is managed with the two following functions: - HAL_TIM_DMABurst_WriteStart() - HAL_TIM_DMABurst_ReadStart() - - *** Callback registration *** - ============================================= - - [..] - The compilation define USE_HAL_TIM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_TIM_RegisterCallback() to register a callback. - HAL_TIM_RegisterCallback() takes as parameters the HAL peripheral handle, - the Callback ID and a pointer to the user callback function. - - [..] - Use function HAL_TIM_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_TIM_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - - [..] - These functions allow to register/unregister following callbacks: - (+) Base_MspInitCallback : TIM Base Msp Init Callback. - (+) Base_MspDeInitCallback : TIM Base Msp DeInit Callback. - (+) IC_MspInitCallback : TIM IC Msp Init Callback. - (+) IC_MspDeInitCallback : TIM IC Msp DeInit Callback. - (+) OC_MspInitCallback : TIM OC Msp Init Callback. - (+) OC_MspDeInitCallback : TIM OC Msp DeInit Callback. - (+) PWM_MspInitCallback : TIM PWM Msp Init Callback. - (+) PWM_MspDeInitCallback : TIM PWM Msp DeInit Callback. - (+) OnePulse_MspInitCallback : TIM One Pulse Msp Init Callback. - (+) OnePulse_MspDeInitCallback : TIM One Pulse Msp DeInit Callback. - (+) Encoder_MspInitCallback : TIM Encoder Msp Init Callback. - (+) Encoder_MspDeInitCallback : TIM Encoder Msp DeInit Callback. - (+) HallSensor_MspInitCallback : TIM Hall Sensor Msp Init Callback. - (+) HallSensor_MspDeInitCallback : TIM Hall Sensor Msp DeInit Callback. - (+) PeriodElapsedCallback : TIM Period Elapsed Callback. - (+) PeriodElapsedHalfCpltCallback : TIM Period Elapsed half complete Callback. - (+) TriggerCallback : TIM Trigger Callback. - (+) TriggerHalfCpltCallback : TIM Trigger half complete Callback. - (+) IC_CaptureCallback : TIM Input Capture Callback. - (+) IC_CaptureHalfCpltCallback : TIM Input Capture half complete Callback. - (+) OC_DelayElapsedCallback : TIM Output Compare Delay Elapsed Callback. - (+) PWM_PulseFinishedCallback : TIM PWM Pulse Finished Callback. - (+) PWM_PulseFinishedHalfCpltCallback : TIM PWM Pulse Finished half complete Callback. - (+) ErrorCallback : TIM Error Callback. - (+) CommutationCallback : TIM Commutation Callback. - (+) CommutationHalfCpltCallback : TIM Commutation half complete Callback. - (+) BreakCallback : TIM Break Callback. - - [..] -By default, after the Init and when the state is HAL_TIM_STATE_RESET -all interrupt callbacks are set to the corresponding weak functions: - examples HAL_TIM_TriggerCallback(), HAL_TIM_ErrorCallback(). - - [..] - Exception done for MspInit and MspDeInit functions that are reset to the legacy weak - functionalities in the Init / DeInit only when these callbacks are null - (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init / DeInit - keep and use the user MspInit / MspDeInit callbacks(registered beforehand) - - [..] - Callbacks can be registered / unregistered in HAL_TIM_STATE_READY state only. - Exception done MspInit / MspDeInit that can be registered / unregistered - in HAL_TIM_STATE_READY or HAL_TIM_STATE_RESET state, - thus registered(user) MspInit / DeInit callbacks can be used during the Init / DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_TIM_RegisterCallback() before calling DeInit or Init function. - - [..] - When The compilation define USE_HAL_TIM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup TIM TIM - * @brief TIM HAL module driver - * @{ - */ - -#ifdef HAL_TIM_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup TIM_Private_Functions - * @{ - */ -static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); -static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); -static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource); -static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig); -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup TIM_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @defgroup TIM_Exported_Functions_Group1 TIM Time Base functions - * @brief Time Base functions - * -@verbatim - ============================================================================== - ##### Time Base functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM base. - (+) De-initialize the TIM base. - (+) Start the Time Base. - (+) Stop the Time Base. - (+) Start the Time Base and enable interrupt. - (+) Stop the Time Base and disable interrupt. - (+) Start the Time Base and enable DMA transfer. - (+) Stop the Time Base and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Time base Unit according to the specified - * parameters in the TIM_HandleTypeDef and initialize the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init() - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->Base_MspInitCallback == NULL) - { - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->Base_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_TIM_Base_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Set the Time Base configuration */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM Base peripheral - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->Base_MspDeInitCallback == NULL) - { - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - } - /* DeInit the low level hardware */ - htim->Base_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_Base_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Base MSP. - * @param htim TIM Base handle - * @retval None - */ -__weak void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Base_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Base MSP. - * @param htim TIM Base handle - * @retval None - */ -__weak void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Base_MspDeInit could be implemented in the user file - */ -} - - -/** - * @brief Starts the TIM Base generation. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Check the TIM state */ - if (htim->State != HAL_TIM_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Base generation in interrupt mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Check the TIM state */ - if (htim->State != HAL_TIM_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Enable the TIM Update interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation in interrupt mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Disable the TIM Update interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_UPDATE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Base generation in DMA mode. - * @param htim TIM Base handle - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); - - /* Set the TIM state */ - if (htim->State == HAL_TIM_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->State == HAL_TIM_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - htim->State = HAL_TIM_STATE_BUSY; - } - } - else - { - return HAL_ERROR; - } - - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)pData, (uint32_t)&htim->Instance->ARR, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Update DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_UPDATE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation in DMA mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); - - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_UPDATE); - - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group2 TIM Output Compare functions - * @brief TIM Output Compare functions - * -@verbatim - ============================================================================== - ##### TIM Output Compare functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Output Compare. - (+) De-initialize the TIM Output Compare. - (+) Start the TIM Output Compare. - (+) Stop the TIM Output Compare. - (+) Start the TIM Output Compare and enable interrupt. - (+) Stop the TIM Output Compare and disable interrupt. - (+) Start the TIM Output Compare and enable DMA transfer. - (+) Stop the TIM Output Compare and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Output Compare according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_OC_DeInit() before HAL_TIM_OC_Init() - * @param htim TIM Output Compare handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->OC_MspInitCallback == NULL) - { - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->OC_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OC_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the Output Compare */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM Output Compare handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->OC_MspDeInitCallback == NULL) - { - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - } - /* DeInit the low level hardware */ - htim->OC_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OC_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Output Compare MSP. - * @param htim TIM Output Compare handle - * @retval None - */ -__weak void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Output Compare MSP. - * @param htim TIM Output Compare handle - * @retval None - */ -__weak void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Output Compare signal generation. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Output Compare signal generation. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Output Compare signal generation in interrupt mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in interrupt mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Output Compare signal generation in DMA mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in DMA mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group3 TIM PWM functions - * @brief TIM PWM functions - * -@verbatim - ============================================================================== - ##### TIM PWM functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM PWM. - (+) De-initialize the TIM PWM. - (+) Start the TIM PWM. - (+) Stop the TIM PWM. - (+) Start the TIM PWM and enable interrupt. - (+) Stop the TIM PWM and disable interrupt. - (+) Start the TIM PWM and enable DMA transfer. - (+) Stop the TIM PWM and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM PWM Time Base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init() - * @param htim TIM PWM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->PWM_MspInitCallback == NULL) - { - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->PWM_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_PWM_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the PWM */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM PWM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->PWM_MspDeInitCallback == NULL) - { - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - } - /* DeInit the low level hardware */ - htim->PWM_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_PWM_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM PWM MSP. - * @param htim TIM PWM handle - * @retval None - */ -__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM PWM MSP. - * @param htim TIM PWM handle - * @retval None - */ -__weak void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the PWM signal generation. - * @param htim TIM handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the PWM signal generation. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the PWM signal generation in interrupt mode. - * @param htim TIM PWM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the PWM signal generation in interrupt mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM PWM signal generation in DMA mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Capture/Compare 3 request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM PWM signal generation in DMA mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group4 TIM Input Capture functions - * @brief TIM Input Capture functions - * -@verbatim - ============================================================================== - ##### TIM Input Capture functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Input Capture. - (+) De-initialize the TIM Input Capture. - (+) Start the TIM Input Capture. - (+) Stop the TIM Input Capture. - (+) Start the TIM Input Capture and enable interrupt. - (+) Stop the TIM Input Capture and disable interrupt. - (+) Start the TIM Input Capture and enable DMA transfer. - (+) Stop the TIM Input Capture and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Input Capture Time base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_IC_DeInit() before HAL_TIM_IC_Init() - * @param htim TIM Input Capture handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->IC_MspInitCallback == NULL) - { - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->IC_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_IC_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the input capture */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM Input Capture handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->IC_MspDeInitCallback == NULL) - { - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - } - /* DeInit the low level hardware */ - htim->IC_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_IC_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Input Capture MSP. - * @param htim TIM Input Capture handle - * @retval None - */ -__weak void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Input Capture MSP. - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Input Capture measurement. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Input Capture measurement. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Input Capture measurement in interrupt mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Input Capture measurement in interrupt mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Input Capture measurement in DMA mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The destination Buffer address. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); - - /* Set the TIM channel state */ - if ((channel_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->CCR3, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->CCR4, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Input Capture measurement in DMA mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group5 TIM One Pulse functions - * @brief TIM One Pulse functions - * -@verbatim - ============================================================================== - ##### TIM One Pulse functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM One Pulse. - (+) De-initialize the TIM One Pulse. - (+) Start the TIM One Pulse. - (+) Stop the TIM One Pulse. - (+) Start the TIM One Pulse and enable interrupt. - (+) Stop the TIM One Pulse and disable interrupt. - (+) Start the TIM One Pulse and enable DMA transfer. - (+) Stop the TIM One Pulse and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM One Pulse Time Base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_OnePulse_DeInit() before HAL_TIM_OnePulse_Init() - * @note When the timer instance is initialized in One Pulse mode, timer - * channels 1 and channel 2 are reserved and cannot be used for other - * purpose. - * @param htim TIM One Pulse handle - * @param OnePulseMode Select the One pulse mode. - * This parameter can be one of the following values: - * @arg TIM_OPMODE_SINGLE: Only one pulse will be generated. - * @arg TIM_OPMODE_REPETITIVE: Repetitive pulses will be generated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_OPM_MODE(OnePulseMode)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->OnePulse_MspInitCallback == NULL) - { - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->OnePulse_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OnePulse_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Configure the Time base in the One Pulse Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Reset the OPM Bit */ - htim->Instance->CR1 &= ~TIM_CR1_OPM; - - /* Configure the OPM Mode */ - htim->Instance->CR1 |= OnePulseMode; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM One Pulse - * @param htim TIM One Pulse handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->OnePulse_MspDeInitCallback == NULL) - { - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - } - /* DeInit the low level hardware */ - htim->OnePulse_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_OnePulse_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM One Pulse MSP. - * @param htim TIM One Pulse handle - * @retval None - */ -__weak void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OnePulse_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM One Pulse MSP. - * @param htim TIM One Pulse handle - * @retval None - */ -__weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OnePulse_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM One Pulse signal generation. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together - - No need to enable the counter, it's enabled automatically by hardware - (the counter starts in response to a stimulus and generate a pulse */ - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Disable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM One Pulse signal generation in interrupt mode. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together - - No need to enable the counter, it's enabled automatically by hardware - (the counter starts in response to a stimulus and generate a pulse */ - - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation in interrupt mode. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - - /* Disable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group6 TIM Encoder functions - * @brief TIM Encoder functions - * -@verbatim - ============================================================================== - ##### TIM Encoder functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Encoder. - (+) De-initialize the TIM Encoder. - (+) Start the TIM Encoder. - (+) Stop the TIM Encoder. - (+) Start the TIM Encoder and enable interrupt. - (+) Stop the TIM Encoder and disable interrupt. - (+) Start the TIM Encoder and enable DMA transfer. - (+) Stop the TIM Encoder and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Encoder Interface and initialize the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_Encoder_DeInit() before HAL_TIM_Encoder_Init() - * @note Encoder mode and External clock mode 2 are not compatible and must not be selected together - * Ex: A call for @ref HAL_TIM_Encoder_Init will erase the settings of @ref HAL_TIM_ConfigClockSource - * using TIM_CLOCKSOURCE_ETRMODE2 and vice versa - * @note When the timer instance is initialized in Encoder mode, timer - * channels 1 and channel 2 are reserved and cannot be used for other - * purpose. - * @param htim TIM Encoder Interface handle - * @param sConfig TIM Encoder Interface configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig) -{ - uint32_t tmpsmcr; - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - assert_param(IS_TIM_ENCODER_MODE(sConfig->EncoderMode)); - assert_param(IS_TIM_IC_SELECTION(sConfig->IC1Selection)); - assert_param(IS_TIM_IC_SELECTION(sConfig->IC2Selection)); - assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC1Polarity)); - assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC2Polarity)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->Encoder_MspInitCallback == NULL) - { - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->Encoder_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_Encoder_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Reset the SMS and ECE bits */ - htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); - - /* Configure the Time base in the Encoder Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = htim->Instance->CCMR1; - - /* Get the TIMx CCER register value */ - tmpccer = htim->Instance->CCER; - - /* Set the encoder Mode */ - tmpsmcr |= sConfig->EncoderMode; - - /* Select the Capture Compare 1 and the Capture Compare 2 as input */ - tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); - tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); - - /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */ - tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC); - tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); - tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); - tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); - - /* Set the TI1 and the TI2 Polarities */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); - tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); - tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); - - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - - /* Write to TIMx CCMR1 */ - htim->Instance->CCMR1 = tmpccmr1; - - /* Write to TIMx CCER */ - htim->Instance->CCER = tmpccer; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - - -/** - * @brief DeInitializes the TIM Encoder interface - * @param htim TIM Encoder Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->Encoder_MspDeInitCallback == NULL) - { - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - } - /* DeInit the low level hardware */ - htim->Encoder_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_Encoder_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Encoder Interface MSP. - * @param htim TIM Encoder Interface handle - * @retval None - */ -__weak void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Encoder_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Encoder Interface MSP. - * @param htim TIM Encoder Interface handle - * @retval None - */ -__weak void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Encoder_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Encoder Interface. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - - /* Enable the encoder interface channels */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - break; - } - } - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - break; - } - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Encoder Interface in interrupt mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - - /* Enable the encoder interface channels */ - /* Enable the capture compare Interrupts 1 and/or 2 */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - } - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface in interrupt mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - if (Channel == TIM_CHANNEL_1) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 1 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - } - else if (Channel == TIM_CHANNEL_2) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 2 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - } - else - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 1 and 2 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Encoder Interface in DMA mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @param pData1 The destination Buffer address for IC1. - * @param pData2 The destination Buffer address for IC2. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, - uint32_t *pData2, uint16_t Length) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData1 == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_2_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData2 == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - else - { - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (channel_2_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((((pData1 == NULL) || (pData2 == NULL))) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError; - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - - default: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface in DMA mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - if (Channel == TIM_CHANNEL_1) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 1 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - } - else if (Channel == TIM_CHANNEL_2) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 2 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - } - else - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 1 and 2 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ -/** @defgroup TIM_Exported_Functions_Group7 TIM IRQ handler management - * @brief TIM IRQ handler management - * -@verbatim - ============================================================================== - ##### IRQ handler management ##### - ============================================================================== - [..] - This section provides Timer IRQ handler function. - -@endverbatim - * @{ - */ -/** - * @brief This function handles TIM interrupts requests. - * @param htim TIM handle - * @retval None - */ -void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) -{ - /* Capture compare 1 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) - { - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - /* Input capture event */ - if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - } - /* Capture compare 2 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - /* Input capture event */ - if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* Capture compare 3 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - /* Input capture event */ - if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* Capture compare 4 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - /* Input capture event */ - if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* TIM Update event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedCallback(htim); -#else - HAL_TIM_PeriodElapsedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM Break input event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->BreakCallback(htim); -#else - HAL_TIMEx_BreakCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM Trigger detection event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerCallback(htim); -#else - HAL_TIM_TriggerCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM commutation event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationCallback(htim); -#else - HAL_TIMEx_CommutCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions - * @brief TIM Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Configure The Input Output channels for OC, PWM, IC or One Pulse mode. - (+) Configure External Clock source. - (+) Configure Complementary channels, break features and dead time. - (+) Configure Master and the Slave synchronization. - (+) Configure the DMA Burst Mode. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the TIM Output Compare Channels according to the specified - * parameters in the TIM_OC_InitTypeDef. - * @param htim TIM Output Compare handle - * @param sConfig TIM Output Compare configuration structure - * @param Channel TIM Channels to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, - TIM_OC_InitTypeDef *sConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CHANNELS(Channel)); - assert_param(IS_TIM_OC_MODE(sConfig->OCMode)); - assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); - - /* Process Locked */ - __HAL_LOCK(htim); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 1 in Output Compare */ - TIM_OC1_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 2 in Output Compare */ - TIM_OC2_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 3 in Output Compare */ - TIM_OC3_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 4 in Output Compare */ - TIM_OC4_SetConfig(htim->Instance, sConfig); - break; - } - - default: - status = HAL_ERROR; - break; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM Input Capture Channels according to the specified - * parameters in the TIM_IC_InitTypeDef. - * @param htim TIM IC handle - * @param sConfig TIM Input Capture configuration structure - * @param Channel TIM Channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_IC_POLARITY(sConfig->ICPolarity)); - assert_param(IS_TIM_IC_SELECTION(sConfig->ICSelection)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->ICPrescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->ICFilter)); - - /* Process Locked */ - __HAL_LOCK(htim); - - if (Channel == TIM_CHANNEL_1) - { - /* TI1 Configuration */ - TIM_TI1_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - - /* Set the IC1PSC value */ - htim->Instance->CCMR1 |= sConfig->ICPrescaler; - } - else if (Channel == TIM_CHANNEL_2) - { - /* TI2 Configuration */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_TI2_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC2PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; - - /* Set the IC2PSC value */ - htim->Instance->CCMR1 |= (sConfig->ICPrescaler << 8U); - } - else if (Channel == TIM_CHANNEL_3) - { - /* TI3 Configuration */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - TIM_TI3_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC3PSC Bits */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC; - - /* Set the IC3PSC value */ - htim->Instance->CCMR2 |= sConfig->ICPrescaler; - } - else if (Channel == TIM_CHANNEL_4) - { - /* TI4 Configuration */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - TIM_TI4_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC4PSC Bits */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC; - - /* Set the IC4PSC value */ - htim->Instance->CCMR2 |= (sConfig->ICPrescaler << 8U); - } - else - { - status = HAL_ERROR; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM PWM channels according to the specified - * parameters in the TIM_OC_InitTypeDef. - * @param htim TIM PWM handle - * @param sConfig TIM PWM configuration structure - * @param Channel TIM Channels to be configured - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, - TIM_OC_InitTypeDef *sConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CHANNELS(Channel)); - assert_param(IS_TIM_PWM_MODE(sConfig->OCMode)); - assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); - assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode)); - - /* Process Locked */ - __HAL_LOCK(htim); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Configure the Channel 1 in PWM mode */ - TIM_OC1_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel1 */ - htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; - htim->Instance->CCMR1 |= sConfig->OCFastMode; - break; - } - - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Configure the Channel 2 in PWM mode */ - TIM_OC2_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel2 */ - htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; - htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Configure the Channel 3 in PWM mode */ - TIM_OC3_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel3 */ - htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; - htim->Instance->CCMR2 |= sConfig->OCFastMode; - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Configure the Channel 4 in PWM mode */ - TIM_OC4_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel4 */ - htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; - htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; - break; - } - - default: - status = HAL_ERROR; - break; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM One Pulse Channels according to the specified - * parameters in the TIM_OnePulse_InitTypeDef. - * @param htim TIM One Pulse handle - * @param sConfig TIM One Pulse configuration structure - * @param OutputChannel TIM output channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @param InputChannel TIM input Channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @note To output a waveform with a minimum delay user can enable the fast - * mode by calling the @ref __HAL_TIM_ENABLE_OCxFAST macro. Then CCx - * output is forced in response to the edge detection on TIx input, - * without taking in account the comparison. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, - uint32_t OutputChannel, uint32_t InputChannel) -{ - HAL_StatusTypeDef status = HAL_OK; - TIM_OC_InitTypeDef temp1; - - /* Check the parameters */ - assert_param(IS_TIM_OPM_CHANNELS(OutputChannel)); - assert_param(IS_TIM_OPM_CHANNELS(InputChannel)); - - if (OutputChannel != InputChannel) - { - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Extract the Output compare configuration from sConfig structure */ - temp1.OCMode = sConfig->OCMode; - temp1.Pulse = sConfig->Pulse; - temp1.OCPolarity = sConfig->OCPolarity; - temp1.OCNPolarity = sConfig->OCNPolarity; - temp1.OCIdleState = sConfig->OCIdleState; - temp1.OCNIdleState = sConfig->OCNIdleState; - - switch (OutputChannel) - { - case TIM_CHANNEL_1: - { - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - TIM_OC1_SetConfig(htim->Instance, &temp1); - break; - } - - case TIM_CHANNEL_2: - { - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_OC2_SetConfig(htim->Instance, &temp1); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - switch (InputChannel) - { - case TIM_CHANNEL_1: - { - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - TIM_TI1_SetConfig(htim->Instance, sConfig->ICPolarity, - sConfig->ICSelection, sConfig->ICFilter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - - /* Select the Trigger source */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI1FP1; - - /* Select the Slave Mode */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; - break; - } - - case TIM_CHANNEL_2: - { - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_TI2_SetConfig(htim->Instance, sConfig->ICPolarity, - sConfig->ICSelection, sConfig->ICFilter); - - /* Reset the IC2PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; - - /* Select the Trigger source */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI2FP2; - - /* Select the Slave Mode */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; - break; - } - - default: - status = HAL_ERROR; - break; - } - } - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Configure the DMA Burst to transfer Data from the memory to the TIM peripheral - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @note This function should be used only when BurstLength is equal to DMA data transfer length. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) -{ - HAL_StatusTypeDef status; - - status = HAL_TIM_DMABurst_MultiWriteStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, - ((BurstLength) >> 8U) + 1U); - - - - return status; -} - -/** - * @brief Configure the DMA Burst to transfer multiple Data from the memory to the TIM peripheral - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @param DataLength Data length. This parameter can be one value - * between 1 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - assert_param(IS_TIM_DMA_LENGTH(BurstLength)); - assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); - - if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) - { - if ((BurstBuffer == NULL) && (BurstLength > 0U)) - { - return HAL_ERROR; - } - else - { - htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; - } - } - else - { - /* nothing to do */ - } - - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_COM: - { - /* Set the DMA commutation callbacks */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_TRIGGER: - { - /* Set the DMA trigger callbacks */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; - htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Configure the DMA Burst Mode */ - htim->Instance->DCR = (BurstBaseAddress | BurstLength); - /* Enable the TIM DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM DMA Burst mode - * @param htim TIM handle - * @param BurstRequestSrc TIM DMA Request sources to disable - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - - /* Abort the DMA transfer (at least disable the DMA stream) */ - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - break; - } - case TIM_DMA_CC1: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - case TIM_DMA_CC2: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - case TIM_DMA_CC3: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - case TIM_DMA_CC4: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - case TIM_DMA_COM: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); - break; - } - case TIM_DMA_TRIGGER: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - } - - /* Return function status */ - return status; -} - -/** - * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @note This function should be used only when BurstLength is equal to DMA data transfer length. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) -{ - HAL_StatusTypeDef status; - - status = HAL_TIM_DMABurst_MultiReadStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, - ((BurstLength) >> 8U) + 1U); - - - return status; -} - -/** - * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @param DataLength Data length. This parameter can be one value - * between 1 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - assert_param(IS_TIM_DMA_LENGTH(BurstLength)); - assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); - - if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) - { - if ((BurstBuffer == NULL) && (BurstLength > 0U)) - { - return HAL_ERROR; - } - else - { - htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; - } - } - else - { - /* nothing to do */ - } - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC3: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC4: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_COM: - { - /* Set the DMA commutation callbacks */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_TRIGGER: - { - /* Set the DMA trigger callbacks */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; - htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Configure the DMA Burst Mode */ - htim->Instance->DCR = (BurstBaseAddress | BurstLength); - - /* Enable the TIM DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stop the DMA burst reading - * @param htim TIM handle - * @param BurstRequestSrc TIM DMA Request sources to disable. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - - /* Abort the DMA transfer (at least disable the DMA stream) */ - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - break; - } - case TIM_DMA_CC1: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - case TIM_DMA_CC2: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - case TIM_DMA_CC3: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - case TIM_DMA_CC4: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - case TIM_DMA_COM: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); - break; - } - case TIM_DMA_TRIGGER: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - } - - /* Return function status */ - return status; -} - -/** - * @brief Generate a software event - * @param htim TIM handle - * @param EventSource specifies the event source. - * This parameter can be one of the following values: - * @arg TIM_EVENTSOURCE_UPDATE: Timer update Event source - * @arg TIM_EVENTSOURCE_CC1: Timer Capture Compare 1 Event source - * @arg TIM_EVENTSOURCE_CC2: Timer Capture Compare 2 Event source - * @arg TIM_EVENTSOURCE_CC3: Timer Capture Compare 3 Event source - * @arg TIM_EVENTSOURCE_CC4: Timer Capture Compare 4 Event source - * @arg TIM_EVENTSOURCE_COM: Timer COM event source - * @arg TIM_EVENTSOURCE_TRIGGER: Timer Trigger Event source - * @arg TIM_EVENTSOURCE_BREAK: Timer Break event source - * @note Basic timers can only generate an update event. - * @note TIM_EVENTSOURCE_COM is relevant only with advanced timer instances. - * @note TIM_EVENTSOURCE_BREAK are relevant only for timer instances - * supporting a break input. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_EVENT_SOURCE(EventSource)); - - /* Process Locked */ - __HAL_LOCK(htim); - - /* Change the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Set the event sources */ - htim->Instance->EGR = EventSource; - - /* Change the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Configures the OCRef clear feature - * @param htim TIM handle - * @param sClearInputConfig pointer to a TIM_ClearInputConfigTypeDef structure that - * contains the OCREF clear feature and parameters for the TIM peripheral. - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, - TIM_ClearInputConfigTypeDef *sClearInputConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_OCXREF_CLEAR_INSTANCE(htim->Instance)); - assert_param(IS_TIM_CLEARINPUT_SOURCE(sClearInputConfig->ClearInputSource)); - - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - switch (sClearInputConfig->ClearInputSource) - { - case TIM_CLEARINPUTSOURCE_NONE: - { - /* Clear the OCREF clear selection bit and the the ETR Bits */ - CLEAR_BIT(htim->Instance->SMCR, (TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP)); - break; - } - - case TIM_CLEARINPUTSOURCE_ETR: - { - /* Check the parameters */ - assert_param(IS_TIM_CLEARINPUT_POLARITY(sClearInputConfig->ClearInputPolarity)); - assert_param(IS_TIM_CLEARINPUT_PRESCALER(sClearInputConfig->ClearInputPrescaler)); - assert_param(IS_TIM_CLEARINPUT_FILTER(sClearInputConfig->ClearInputFilter)); - - /* When OCRef clear feature is used with ETR source, ETR prescaler must be off */ - if (sClearInputConfig->ClearInputPrescaler != TIM_CLEARINPUTPRESCALER_DIV1) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - TIM_ETR_SetConfig(htim->Instance, - sClearInputConfig->ClearInputPrescaler, - sClearInputConfig->ClearInputPolarity, - sClearInputConfig->ClearInputFilter); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - switch (Channel) - { - case TIM_CHANNEL_1: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 1 */ - SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); - } - else - { - /* Disable the OCREF clear feature for Channel 1 */ - CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); - } - break; - } - case TIM_CHANNEL_2: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 2 */ - SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); - } - else - { - /* Disable the OCREF clear feature for Channel 2 */ - CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); - } - break; - } - case TIM_CHANNEL_3: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 3 */ - SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); - } - else - { - /* Disable the OCREF clear feature for Channel 3 */ - CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); - } - break; - } - case TIM_CHANNEL_4: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 4 */ - SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); - } - else - { - /* Disable the OCREF clear feature for Channel 4 */ - CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); - } - break; - } - default: - break; - } - } - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Configures the clock source to be used - * @param htim TIM handle - * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that - * contains the clock source information for the TIM peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Check the parameters */ - assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource)); - - /* Reset the SMS, TS, ECE, ETPS and ETRF bits */ - tmpsmcr = htim->Instance->SMCR; - tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); - tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - htim->Instance->SMCR = tmpsmcr; - - switch (sClockSourceConfig->ClockSource) - { - case TIM_CLOCKSOURCE_INTERNAL: - { - assert_param(IS_TIM_INSTANCE(htim->Instance)); - break; - } - - case TIM_CLOCKSOURCE_ETRMODE1: - { - /* Check whether or not the timer instance supports external trigger input mode 1 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); - - /* Check ETR input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - /* Configure the ETR Clock source */ - TIM_ETR_SetConfig(htim->Instance, - sClockSourceConfig->ClockPrescaler, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - - /* Select the External clock mode1 and the ETRF trigger */ - tmpsmcr = htim->Instance->SMCR; - tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - break; - } - - case TIM_CLOCKSOURCE_ETRMODE2: - { - /* Check whether or not the timer instance supports external trigger input mode 2 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(htim->Instance)); - - /* Check ETR input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - /* Configure the ETR Clock source */ - TIM_ETR_SetConfig(htim->Instance, - sClockSourceConfig->ClockPrescaler, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - /* Enable the External clock mode2 */ - htim->Instance->SMCR |= TIM_SMCR_ECE; - break; - } - - case TIM_CLOCKSOURCE_TI1: - { - /* Check whether or not the timer instance supports external clock mode 1 */ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI1 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI1_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); - break; - } - - case TIM_CLOCKSOURCE_TI2: - { - /* Check whether or not the timer instance supports external clock mode 1 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI2 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI2_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); - break; - } - - case TIM_CLOCKSOURCE_TI1ED: - { - /* Check whether or not the timer instance supports external clock mode 1 */ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI1 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI1_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); - break; - } - - case TIM_CLOCKSOURCE_ITR0: - case TIM_CLOCKSOURCE_ITR1: - case TIM_CLOCKSOURCE_ITR2: - case TIM_CLOCKSOURCE_ITR3: - { - /* Check whether or not the timer instance supports internal trigger input */ - assert_param(IS_TIM_CLOCKSOURCE_ITRX_INSTANCE(htim->Instance)); - - TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); - break; - } - - default: - status = HAL_ERROR; - break; - } - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Selects the signal connected to the TI1 input: direct from CH1_input - * or a XOR combination between CH1_input, CH2_input & CH3_input - * @param htim TIM handle. - * @param TI1_Selection Indicate whether or not channel 1 is connected to the - * output of a XOR gate. - * This parameter can be one of the following values: - * @arg TIM_TI1SELECTION_CH1: The TIMx_CH1 pin is connected to TI1 input - * @arg TIM_TI1SELECTION_XORCOMBINATION: The TIMx_CH1, CH2 and CH3 - * pins are connected to the TI1 input (XOR combination) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection) -{ - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_XOR_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TI1SELECTION(TI1_Selection)); - - /* Get the TIMx CR2 register value */ - tmpcr2 = htim->Instance->CR2; - - /* Reset the TI1 selection */ - tmpcr2 &= ~TIM_CR2_TI1S; - - /* Set the TI1 selection */ - tmpcr2 |= TI1_Selection; - - /* Write to TIMxCR2 */ - htim->Instance->CR2 = tmpcr2; - - return HAL_OK; -} - -/** - * @brief Configures the TIM in Slave mode - * @param htim TIM handle. - * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that - * contains the selected trigger (internal trigger input, filtered - * timer input or external trigger input) and the Slave mode - * (Disable, Reset, Gated, Trigger, External clock mode 1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - /* Check the parameters */ - assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); - assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); - - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - /* Disable Trigger Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_TRIGGER); - - /* Disable Trigger DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIM in Slave mode in interrupt mode - * @param htim TIM handle. - * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that - * contains the selected trigger (internal trigger input, filtered - * timer input or external trigger input) and the Slave mode - * (Disable, Reset, Gated, Trigger, External clock mode 1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - /* Check the parameters */ - assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); - assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); - - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - /* Enable Trigger Interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_TRIGGER); - - /* Disable Trigger DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Read the captured value from Capture Compare unit - * @param htim TIM handle. - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval Captured value - */ -uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpreg = 0U; - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Return the capture 1 value */ - tmpreg = htim->Instance->CCR1; - - break; - } - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Return the capture 2 value */ - tmpreg = htim->Instance->CCR2; - - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Return the capture 3 value */ - tmpreg = htim->Instance->CCR3; - - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Return the capture 4 value */ - tmpreg = htim->Instance->CCR4; - - break; - } - - default: - break; - } - - return tmpreg; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions - * @brief TIM Callbacks functions - * -@verbatim - ============================================================================== - ##### TIM Callbacks functions ##### - ============================================================================== - [..] - This section provides TIM callback functions: - (+) TIM Period elapsed callback - (+) TIM Output Compare callback - (+) TIM Input capture callback - (+) TIM Trigger callback - (+) TIM Error callback - -@endverbatim - * @{ - */ - -/** - * @brief Period elapsed callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PeriodElapsedCallback could be implemented in the user file - */ -} - -/** - * @brief Period elapsed half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PeriodElapsedHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Output Compare callback in non-blocking mode - * @param htim TIM OC handle - * @retval None - */ -__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file - */ -} - -/** - * @brief Input Capture callback in non-blocking mode - * @param htim TIM IC handle - * @retval None - */ -__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_CaptureCallback could be implemented in the user file - */ -} - -/** - * @brief Input Capture half complete callback in non-blocking mode - * @param htim TIM IC handle - * @retval None - */ -__weak void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_CaptureHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief PWM Pulse finished callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file - */ -} - -/** - * @brief PWM Pulse finished half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_PulseFinishedHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Trigger detection callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_TriggerCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Trigger detection half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_TriggerHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Timer error callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_ErrorCallback could be implemented in the user file - */ -} - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User TIM callback to be used instead of the weak predefined callback - * @param htim tim handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID - * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID - * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID - * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID - * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID - * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID - * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID - * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID - * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID - * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID - * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID - * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID - * @param pCallback pointer to the callback function - * @retval status - */ -HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, - pTIM_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(htim); - - if (htim->State == HAL_TIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - htim->Base_MspInitCallback = pCallback; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - htim->Base_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - htim->IC_MspInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - htim->IC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - htim->OC_MspInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - htim->OC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - htim->PWM_MspInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - htim->PWM_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - htim->OnePulse_MspInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - htim->OnePulse_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - htim->Encoder_MspInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - htim->Encoder_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - htim->HallSensor_MspInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - htim->HallSensor_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_CB_ID : - htim->PeriodElapsedCallback = pCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : - htim->PeriodElapsedHalfCpltCallback = pCallback; - break; - - case HAL_TIM_TRIGGER_CB_ID : - htim->TriggerCallback = pCallback; - break; - - case HAL_TIM_TRIGGER_HALF_CB_ID : - htim->TriggerHalfCpltCallback = pCallback; - break; - - case HAL_TIM_IC_CAPTURE_CB_ID : - htim->IC_CaptureCallback = pCallback; - break; - - case HAL_TIM_IC_CAPTURE_HALF_CB_ID : - htim->IC_CaptureHalfCpltCallback = pCallback; - break; - - case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : - htim->OC_DelayElapsedCallback = pCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : - htim->PWM_PulseFinishedCallback = pCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : - htim->PWM_PulseFinishedHalfCpltCallback = pCallback; - break; - - case HAL_TIM_ERROR_CB_ID : - htim->ErrorCallback = pCallback; - break; - - case HAL_TIM_COMMUTATION_CB_ID : - htim->CommutationCallback = pCallback; - break; - - case HAL_TIM_COMMUTATION_HALF_CB_ID : - htim->CommutationHalfCpltCallback = pCallback; - break; - - case HAL_TIM_BREAK_CB_ID : - htim->BreakCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (htim->State == HAL_TIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - htim->Base_MspInitCallback = pCallback; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - htim->Base_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - htim->IC_MspInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - htim->IC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - htim->OC_MspInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - htim->OC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - htim->PWM_MspInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - htim->PWM_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - htim->OnePulse_MspInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - htim->OnePulse_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - htim->Encoder_MspInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - htim->Encoder_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - htim->HallSensor_MspInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - htim->HallSensor_MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Unregister a TIM callback - * TIM callback is redirected to the weak predefined callback - * @param htim tim handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID - * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID - * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID - * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID - * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID - * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID - * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID - * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID - * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID - * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID - * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID - * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(htim); - - if (htim->State == HAL_TIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - /* Legacy weak Base MspInit Callback */ - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - /* Legacy weak Base Msp DeInit Callback */ - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - /* Legacy weak IC Msp Init Callback */ - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - /* Legacy weak IC Msp DeInit Callback */ - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - /* Legacy weak OC Msp Init Callback */ - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - /* Legacy weak OC Msp DeInit Callback */ - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - /* Legacy weak PWM Msp Init Callback */ - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - /* Legacy weak PWM Msp DeInit Callback */ - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - /* Legacy weak One Pulse Msp Init Callback */ - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - /* Legacy weak One Pulse Msp DeInit Callback */ - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - /* Legacy weak Encoder Msp Init Callback */ - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - /* Legacy weak Encoder Msp DeInit Callback */ - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - /* Legacy weak Hall Sensor Msp Init Callback */ - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - /* Legacy weak Hall Sensor Msp DeInit Callback */ - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - break; - - case HAL_TIM_PERIOD_ELAPSED_CB_ID : - /* Legacy weak Period Elapsed Callback */ - htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : - /* Legacy weak Period Elapsed half complete Callback */ - htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; - break; - - case HAL_TIM_TRIGGER_CB_ID : - /* Legacy weak Trigger Callback */ - htim->TriggerCallback = HAL_TIM_TriggerCallback; - break; - - case HAL_TIM_TRIGGER_HALF_CB_ID : - /* Legacy weak Trigger half complete Callback */ - htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; - break; - - case HAL_TIM_IC_CAPTURE_CB_ID : - /* Legacy weak IC Capture Callback */ - htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; - break; - - case HAL_TIM_IC_CAPTURE_HALF_CB_ID : - /* Legacy weak IC Capture half complete Callback */ - htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; - break; - - case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : - /* Legacy weak OC Delay Elapsed Callback */ - htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : - /* Legacy weak PWM Pulse Finished Callback */ - htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : - /* Legacy weak PWM Pulse Finished half complete Callback */ - htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; - break; - - case HAL_TIM_ERROR_CB_ID : - /* Legacy weak Error Callback */ - htim->ErrorCallback = HAL_TIM_ErrorCallback; - break; - - case HAL_TIM_COMMUTATION_CB_ID : - /* Legacy weak Commutation Callback */ - htim->CommutationCallback = HAL_TIMEx_CommutCallback; - break; - - case HAL_TIM_COMMUTATION_HALF_CB_ID : - /* Legacy weak Commutation half complete Callback */ - htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; - break; - - case HAL_TIM_BREAK_CB_ID : - /* Legacy weak Break Callback */ - htim->BreakCallback = HAL_TIMEx_BreakCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (htim->State == HAL_TIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - /* Legacy weak Base MspInit Callback */ - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - /* Legacy weak Base Msp DeInit Callback */ - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - /* Legacy weak IC Msp Init Callback */ - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - /* Legacy weak IC Msp DeInit Callback */ - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - /* Legacy weak OC Msp Init Callback */ - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - /* Legacy weak OC Msp DeInit Callback */ - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - /* Legacy weak PWM Msp Init Callback */ - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - /* Legacy weak PWM Msp DeInit Callback */ - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - /* Legacy weak One Pulse Msp Init Callback */ - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - /* Legacy weak One Pulse Msp DeInit Callback */ - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - /* Legacy weak Encoder Msp Init Callback */ - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - /* Legacy weak Encoder Msp DeInit Callback */ - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - /* Legacy weak Hall Sensor Msp Init Callback */ - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - /* Legacy weak Hall Sensor Msp DeInit Callback */ - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return status; -} -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions - * @brief TIM Peripheral State functions - * -@verbatim - ============================================================================== - ##### Peripheral State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the TIM Base handle state. - * @param htim TIM Base handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM OC handle state. - * @param htim TIM Output Compare handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM PWM handle state. - * @param htim TIM handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Input Capture handle state. - * @param htim TIM IC handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM One Pulse Mode handle state. - * @param htim TIM OPM handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Encoder Mode handle state. - * @param htim TIM Encoder Interface handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Encoder Mode handle state. - * @param htim TIM handle - * @retval Active channel - */ -HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim) -{ - return htim->Channel; -} - -/** - * @brief Return actual state of the TIM channel. - * @param htim TIM handle - * @param Channel TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @arg TIM_CHANNEL_5: TIM Channel 5 - * @arg TIM_CHANNEL_6: TIM Channel 6 - * @retval TIM Channel state - */ -HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_state; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - - return channel_state; -} - -/** - * @brief Return actual state of a DMA burst operation. - * @param htim TIM handle - * @retval DMA burst state - */ -HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - - return htim->DMABurstState; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Functions TIM Private Functions - * @{ - */ - -/** - * @brief TIM DMA error callback - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMAError(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->ErrorCallback(htim); -#else - HAL_TIM_ErrorCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Delay Pulse complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Delay Pulse half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedHalfCpltCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Capture complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Capture half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureHalfCpltCallback(htim); -#else - HAL_TIM_IC_CaptureHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Period Elapse complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (htim->hdma[TIM_DMA_ID_UPDATE]->Init.Mode == DMA_NORMAL) - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedCallback(htim); -#else - HAL_TIM_PeriodElapsedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Period Elapse half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedHalfCpltCallback(htim); -#else - HAL_TIM_PeriodElapsedHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Trigger callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (htim->hdma[TIM_DMA_ID_TRIGGER]->Init.Mode == DMA_NORMAL) - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerCallback(htim); -#else - HAL_TIM_TriggerCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Trigger half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerHalfCpltCallback(htim); -#else - HAL_TIM_TriggerHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief Time Base configuration - * @param TIMx TIM peripheral - * @param Structure TIM Base configuration structure - * @retval None - */ -void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) -{ - uint32_t tmpcr1; - tmpcr1 = TIMx->CR1; - - /* Set TIM Time Base Unit parameters ---------------------------------------*/ - if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) - { - /* Select the Counter Mode */ - tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); - tmpcr1 |= Structure->CounterMode; - } - - if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) - { - /* Set the clock division */ - tmpcr1 &= ~TIM_CR1_CKD; - tmpcr1 |= (uint32_t)Structure->ClockDivision; - } - - /* Set the auto-reload preload */ - MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); - - TIMx->CR1 = tmpcr1; - - /* Set the Autoreload value */ - TIMx->ARR = (uint32_t)Structure->Period ; - - /* Set the Prescaler value */ - TIMx->PSC = Structure->Prescaler; - - if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) - { - /* Set the Repetition Counter value */ - TIMx->RCR = Structure->RepetitionCounter; - } - - /* Generate an update event to reload the Prescaler - and the repetition counter (only for advanced timer) value immediately */ - TIMx->EGR = TIM_EGR_UG; -} - -/** - * @brief Timer Output Compare 1 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= ~TIM_CCER_CC1E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare Mode Bits */ - tmpccmrx &= ~TIM_CCMR1_OC1M; - tmpccmrx &= ~TIM_CCMR1_CC1S; - /* Select the Output Compare Mode */ - tmpccmrx |= OC_Config->OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC1P; - /* Set the Output Compare Polarity */ - tmpccer |= OC_Config->OCPolarity; - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) - { - /* Check parameters */ - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC1NP; - /* Set the Output N Polarity */ - tmpccer |= OC_Config->OCNPolarity; - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC1NE; - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS1; - tmpcr2 &= ~TIM_CR2_OIS1N; - /* Set the Output Idle state */ - tmpcr2 |= OC_Config->OCIdleState; - /* Set the Output N Idle state */ - tmpcr2 |= OC_Config->OCNIdleState; - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR1 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 2 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR1_OC2M; - tmpccmrx &= ~TIM_CCMR1_CC2S; - - /* Select the Output Compare Mode */ - tmpccmrx |= (OC_Config->OCMode << 8U); - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC2P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 4U); - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) - { - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC2NP; - /* Set the Output N Polarity */ - tmpccer |= (OC_Config->OCNPolarity << 4U); - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC2NE; - - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS2; - tmpcr2 &= ~TIM_CR2_OIS2N; - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 2U); - /* Set the Output N Idle state */ - tmpcr2 |= (OC_Config->OCNIdleState << 2U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR2 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 3 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 3: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC3E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR2_OC3M; - tmpccmrx &= ~TIM_CCMR2_CC3S; - /* Select the Output Compare Mode */ - tmpccmrx |= OC_Config->OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC3P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 8U); - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) - { - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC3NP; - /* Set the Output N Polarity */ - tmpccer |= (OC_Config->OCNPolarity << 8U); - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC3NE; - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS3; - tmpcr2 &= ~TIM_CR2_OIS3N; - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 4U); - /* Set the Output N Idle state */ - tmpcr2 |= (OC_Config->OCNIdleState << 4U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR3 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 4 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= ~TIM_CCER_CC4E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR2_OC4M; - tmpccmrx &= ~TIM_CCMR2_CC4S; - - /* Select the Output Compare Mode */ - tmpccmrx |= (OC_Config->OCMode << 8U); - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC4P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 12U); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS4; - - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 6U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR4 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Slave Timer configuration function - * @param htim TIM handle - * @param sSlaveConfig Slave timer configuration - * @retval None - */ -static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Reset the Trigger Selection Bits */ - tmpsmcr &= ~TIM_SMCR_TS; - /* Set the Input Trigger source */ - tmpsmcr |= sSlaveConfig->InputTrigger; - - /* Reset the slave mode Bits */ - tmpsmcr &= ~TIM_SMCR_SMS; - /* Set the slave mode */ - tmpsmcr |= sSlaveConfig->SlaveMode; - - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - - /* Configure the trigger prescaler, filter, and polarity */ - switch (sSlaveConfig->InputTrigger) - { - case TIM_TS_ETRF: - { - /* Check the parameters */ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPRESCALER(sSlaveConfig->TriggerPrescaler)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - /* Configure the ETR Trigger source */ - TIM_ETR_SetConfig(htim->Instance, - sSlaveConfig->TriggerPrescaler, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_TI1F_ED: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - if (sSlaveConfig->SlaveMode == TIM_SLAVEMODE_GATED) - { - return HAL_ERROR; - } - - /* Disable the Channel 1: Reset the CC1E Bit */ - tmpccer = htim->Instance->CCER; - htim->Instance->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = htim->Instance->CCMR1; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= ((sSlaveConfig->TriggerFilter) << 4U); - - /* Write to TIMx CCMR1 and CCER registers */ - htim->Instance->CCMR1 = tmpccmr1; - htim->Instance->CCER = tmpccer; - break; - } - - case TIM_TS_TI1FP1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - /* Configure TI1 Filter and Polarity */ - TIM_TI1_ConfigInputStage(htim->Instance, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_TI2FP2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - /* Configure TI2 Filter and Polarity */ - TIM_TI2_ConfigInputStage(htim->Instance, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_ITR0: - case TIM_TS_ITR1: - case TIM_TS_ITR2: - case TIM_TS_ITR3: - { - /* Check the parameter */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - break; - } - - default: - status = HAL_ERROR; - break; - } - - return status; -} - -/** - * @brief Configure the TI1 as Input. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 1 is selected to be connected to IC1. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 1 is selected to be connected to IC2. - * @arg TIM_ICSELECTION_TRC: TIM Input 1 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI2FP1 - * (on channel2 path) is used as the input signal. Therefore CCMR1 must be - * protected against un-initialized filter and polarity values. - */ -void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Select the Input */ - if (IS_TIM_CC2_INSTANCE(TIMx) != RESET) - { - tmpccmr1 &= ~TIM_CCMR1_CC1S; - tmpccmr1 |= TIM_ICSelection; - } - else - { - tmpccmr1 |= TIM_CCMR1_CC1S_0; - } - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= ((TIM_ICFilter << 4U) & TIM_CCMR1_IC1F); - - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - tmpccer |= (TIM_ICPolarity & (TIM_CCER_CC1P | TIM_CCER_CC1NP)); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the Polarity and Filter for TI1. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 1: Reset the CC1E Bit */ - tmpccer = TIMx->CCER; - TIMx->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = TIMx->CCMR1; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= (TIM_ICFilter << 4U); - - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - tmpccer |= TIM_ICPolarity; - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI2 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 2 is selected to be connected to IC2. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 2 is selected to be connected to IC1. - * @arg TIM_ICSELECTION_TRC: TIM Input 2 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI1FP2 - * (on channel1 path) is used as the input signal. Therefore CCMR1 must be - * protected against un-initialized filter and polarity values. - */ -static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr1 &= ~TIM_CCMR1_CC2S; - tmpccmr1 |= (TIM_ICSelection << 8U); - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC2F; - tmpccmr1 |= ((TIM_ICFilter << 12U) & TIM_CCMR1_IC2F); - - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= ((TIM_ICPolarity << 4U) & (TIM_CCER_CC2P | TIM_CCER_CC2NP)); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1 ; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the Polarity and Filter for TI2. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC2F; - tmpccmr1 |= (TIM_ICFilter << 12U); - - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= (TIM_ICPolarity << 4U); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1 ; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI3 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 3 is selected to be connected to IC3. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 3 is selected to be connected to IC4. - * @arg TIM_ICSELECTION_TRC: TIM Input 3 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI3FP4 - * (on channel1 path) is used as the input signal. Therefore CCMR2 must be - * protected against un-initialized filter and polarity values. - */ -static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - - /* Disable the Channel 3: Reset the CC3E Bit */ - TIMx->CCER &= ~TIM_CCER_CC3E; - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr2 &= ~TIM_CCMR2_CC3S; - tmpccmr2 |= TIM_ICSelection; - - /* Set the filter */ - tmpccmr2 &= ~TIM_CCMR2_IC3F; - tmpccmr2 |= ((TIM_ICFilter << 4U) & TIM_CCMR2_IC3F); - - /* Select the Polarity and set the CC3E Bit */ - tmpccer &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP); - tmpccer |= ((TIM_ICPolarity << 8U) & (TIM_CCER_CC3P | TIM_CCER_CC3NP)); - - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI4 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 4 is selected to be connected to IC4. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 4 is selected to be connected to IC3. - * @arg TIM_ICSELECTION_TRC: TIM Input 4 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI4FP3 - * (on channel1 path) is used as the input signal. Therefore CCMR2 must be - * protected against un-initialized filter and polarity values. - * @retval None - */ -static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= ~TIM_CCER_CC4E; - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr2 &= ~TIM_CCMR2_CC4S; - tmpccmr2 |= (TIM_ICSelection << 8U); - - /* Set the filter */ - tmpccmr2 &= ~TIM_CCMR2_IC4F; - tmpccmr2 |= ((TIM_ICFilter << 12U) & TIM_CCMR2_IC4F); - - /* Select the Polarity and set the CC4E Bit */ - tmpccer &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP); - tmpccer |= ((TIM_ICPolarity << 12U) & (TIM_CCER_CC4P | TIM_CCER_CC4NP)); - - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer ; -} - -/** - * @brief Selects the Input Trigger source - * @param TIMx to select the TIM peripheral - * @param InputTriggerSource The Input Trigger source. - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal Trigger 0 - * @arg TIM_TS_ITR1: Internal Trigger 1 - * @arg TIM_TS_ITR2: Internal Trigger 2 - * @arg TIM_TS_ITR3: Internal Trigger 3 - * @arg TIM_TS_TI1F_ED: TI1 Edge Detector - * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 - * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 - * @arg TIM_TS_ETRF: External Trigger input - * @retval None - */ -static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource) -{ - uint32_t tmpsmcr; - - /* Get the TIMx SMCR register value */ - tmpsmcr = TIMx->SMCR; - /* Reset the TS Bits */ - tmpsmcr &= ~TIM_SMCR_TS; - /* Set the Input Trigger source and the slave mode*/ - tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} -/** - * @brief Configures the TIMx External Trigger (ETR). - * @param TIMx to select the TIM peripheral - * @param TIM_ExtTRGPrescaler The external Trigger Prescaler. - * This parameter can be one of the following values: - * @arg TIM_ETRPRESCALER_DIV1: ETRP Prescaler OFF. - * @arg TIM_ETRPRESCALER_DIV2: ETRP frequency divided by 2. - * @arg TIM_ETRPRESCALER_DIV4: ETRP frequency divided by 4. - * @arg TIM_ETRPRESCALER_DIV8: ETRP frequency divided by 8. - * @param TIM_ExtTRGPolarity The external Trigger Polarity. - * This parameter can be one of the following values: - * @arg TIM_ETRPOLARITY_INVERTED: active low or falling edge active. - * @arg TIM_ETRPOLARITY_NONINVERTED: active high or rising edge active. - * @param ExtTRGFilter External Trigger Filter. - * This parameter must be a value between 0x00 and 0x0F - * @retval None - */ -void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, - uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter) -{ - uint32_t tmpsmcr; - - tmpsmcr = TIMx->SMCR; - - /* Reset the ETR Bits */ - tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - - /* Set the Prescaler, the Filter value and the Polarity */ - tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); - - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel x. - * @param TIMx to select the TIM peripheral - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @param ChannelState specifies the TIM Channel CCxE bit new state. - * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE. - * @retval None - */ -void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState) -{ - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(TIMx)); - assert_param(IS_TIM_CHANNELS(Channel)); - - tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ - - /* Reset the CCxE Bit */ - TIMx->CCER &= ~tmp; - - /* Set or reset the CCxE Bit */ - TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ -} - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief Reset interrupt callbacks to the legacy weak callbacks. - * @param htim pointer to a TIM_HandleTypeDef structure that contains - * the configuration information for TIM module. - * @retval None - */ -void TIM_ResetCallback(TIM_HandleTypeDef *htim) -{ - /* Reset the TIM callback to the legacy weak callbacks */ - htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; - htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; - htim->TriggerCallback = HAL_TIM_TriggerCallback; - htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; - htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; - htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; - htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; - htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; - htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; - htim->ErrorCallback = HAL_TIM_ErrorCallback; - htim->CommutationCallback = HAL_TIMEx_CommutCallback; - htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; - htim->BreakCallback = HAL_TIMEx_BreakCallback; -} -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -#endif /* HAL_TIM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim.c + * @author MCD Application Team + * @brief TIM HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Timer (TIM) peripheral: + * + TIM Time Base Initialization + * + TIM Time Base Start + * + TIM Time Base Start Interruption + * + TIM Time Base Start DMA + * + TIM Output Compare/PWM Initialization + * + TIM Output Compare/PWM Channel Configuration + * + TIM Output Compare/PWM Start + * + TIM Output Compare/PWM Start Interruption + * + TIM Output Compare/PWM Start DMA + * + TIM Input Capture Initialization + * + TIM Input Capture Channel Configuration + * + TIM Input Capture Start + * + TIM Input Capture Start Interruption + * + TIM Input Capture Start DMA + * + TIM One Pulse Initialization + * + TIM One Pulse Channel Configuration + * + TIM One Pulse Start + * + TIM Encoder Interface Initialization + * + TIM Encoder Interface Start + * + TIM Encoder Interface Start Interruption + * + TIM Encoder Interface Start DMA + * + Commutation Event configuration with Interruption and DMA + * + TIM OCRef clear configuration + * + TIM External Clock configuration + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### TIMER Generic features ##### + ============================================================================== + [..] The Timer features include: + (#) 16-bit up, down, up/down auto-reload counter. + (#) 16-bit programmable prescaler allowing dividing (also on the fly) the + counter clock frequency either by any factor between 1 and 65536. + (#) Up to 4 independent channels for: + (++) Input Capture + (++) Output Compare + (++) PWM generation (Edge and Center-aligned Mode) + (++) One-pulse mode output + (#) Synchronization circuit to control the timer with external signals and to interconnect + several timers together. + (#) Supports incremental encoder for positioning purposes + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the TIM low level resources by implementing the following functions + depending on the selected feature: + (++) Time Base : HAL_TIM_Base_MspInit() + (++) Input Capture : HAL_TIM_IC_MspInit() + (++) Output Compare : HAL_TIM_OC_MspInit() + (++) PWM generation : HAL_TIM_PWM_MspInit() + (++) One-pulse mode output : HAL_TIM_OnePulse_MspInit() + (++) Encoder mode output : HAL_TIM_Encoder_MspInit() + + (#) Initialize the TIM low level resources : + (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); + (##) TIM pins configuration + (+++) Enable the clock for the TIM GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); + + (#) The external Clock can be configured, if needed (the default clock is the + internal clock from the APBx), using the following function: + HAL_TIM_ConfigClockSource, the clock configuration should be done before + any start function. + + (#) Configure the TIM in the desired functioning mode using one of the + Initialization function of this driver: + (++) HAL_TIM_Base_Init: to use the Timer to generate a simple time base + (++) HAL_TIM_OC_Init and HAL_TIM_OC_ConfigChannel: to use the Timer to generate an + Output Compare signal. + (++) HAL_TIM_PWM_Init and HAL_TIM_PWM_ConfigChannel: to use the Timer to generate a + PWM signal. + (++) HAL_TIM_IC_Init and HAL_TIM_IC_ConfigChannel: to use the Timer to measure an + external signal. + (++) HAL_TIM_OnePulse_Init and HAL_TIM_OnePulse_ConfigChannel: to use the Timer + in One Pulse Mode. + (++) HAL_TIM_Encoder_Init: to use the Timer Encoder Interface. + + (#) Activate the TIM peripheral using one of the start functions depending from the feature used: + (++) Time Base : HAL_TIM_Base_Start(), HAL_TIM_Base_Start_DMA(), HAL_TIM_Base_Start_IT() + (++) Input Capture : HAL_TIM_IC_Start(), HAL_TIM_IC_Start_DMA(), HAL_TIM_IC_Start_IT() + (++) Output Compare : HAL_TIM_OC_Start(), HAL_TIM_OC_Start_DMA(), HAL_TIM_OC_Start_IT() + (++) PWM generation : HAL_TIM_PWM_Start(), HAL_TIM_PWM_Start_DMA(), HAL_TIM_PWM_Start_IT() + (++) One-pulse mode output : HAL_TIM_OnePulse_Start(), HAL_TIM_OnePulse_Start_IT() + (++) Encoder mode output : HAL_TIM_Encoder_Start(), HAL_TIM_Encoder_Start_DMA(), HAL_TIM_Encoder_Start_IT(). + + (#) The DMA Burst is managed with the two following functions: + HAL_TIM_DMABurst_WriteStart() + HAL_TIM_DMABurst_ReadStart() + + *** Callback registration *** + ============================================= + + [..] + The compilation define USE_HAL_TIM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_TIM_RegisterCallback() to register a callback. + HAL_TIM_RegisterCallback() takes as parameters the HAL peripheral handle, + the Callback ID and a pointer to the user callback function. + + [..] + Use function HAL_TIM_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_TIM_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + + [..] + These functions allow to register/unregister following callbacks: + (+) Base_MspInitCallback : TIM Base Msp Init Callback. + (+) Base_MspDeInitCallback : TIM Base Msp DeInit Callback. + (+) IC_MspInitCallback : TIM IC Msp Init Callback. + (+) IC_MspDeInitCallback : TIM IC Msp DeInit Callback. + (+) OC_MspInitCallback : TIM OC Msp Init Callback. + (+) OC_MspDeInitCallback : TIM OC Msp DeInit Callback. + (+) PWM_MspInitCallback : TIM PWM Msp Init Callback. + (+) PWM_MspDeInitCallback : TIM PWM Msp DeInit Callback. + (+) OnePulse_MspInitCallback : TIM One Pulse Msp Init Callback. + (+) OnePulse_MspDeInitCallback : TIM One Pulse Msp DeInit Callback. + (+) Encoder_MspInitCallback : TIM Encoder Msp Init Callback. + (+) Encoder_MspDeInitCallback : TIM Encoder Msp DeInit Callback. + (+) HallSensor_MspInitCallback : TIM Hall Sensor Msp Init Callback. + (+) HallSensor_MspDeInitCallback : TIM Hall Sensor Msp DeInit Callback. + (+) PeriodElapsedCallback : TIM Period Elapsed Callback. + (+) PeriodElapsedHalfCpltCallback : TIM Period Elapsed half complete Callback. + (+) TriggerCallback : TIM Trigger Callback. + (+) TriggerHalfCpltCallback : TIM Trigger half complete Callback. + (+) IC_CaptureCallback : TIM Input Capture Callback. + (+) IC_CaptureHalfCpltCallback : TIM Input Capture half complete Callback. + (+) OC_DelayElapsedCallback : TIM Output Compare Delay Elapsed Callback. + (+) PWM_PulseFinishedCallback : TIM PWM Pulse Finished Callback. + (+) PWM_PulseFinishedHalfCpltCallback : TIM PWM Pulse Finished half complete Callback. + (+) ErrorCallback : TIM Error Callback. + (+) CommutationCallback : TIM Commutation Callback. + (+) CommutationHalfCpltCallback : TIM Commutation half complete Callback. + (+) BreakCallback : TIM Break Callback. + + [..] +By default, after the Init and when the state is HAL_TIM_STATE_RESET +all interrupt callbacks are set to the corresponding weak functions: + examples HAL_TIM_TriggerCallback(), HAL_TIM_ErrorCallback(). + + [..] + Exception done for MspInit and MspDeInit functions that are reset to the legacy weak + functionalities in the Init / DeInit only when these callbacks are null + (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init / DeInit + keep and use the user MspInit / MspDeInit callbacks(registered beforehand) + + [..] + Callbacks can be registered / unregistered in HAL_TIM_STATE_READY state only. + Exception done MspInit / MspDeInit that can be registered / unregistered + in HAL_TIM_STATE_READY or HAL_TIM_STATE_RESET state, + thus registered(user) MspInit / DeInit callbacks can be used during the Init / DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_TIM_RegisterCallback() before calling DeInit or Init function. + + [..] + When The compilation define USE_HAL_TIM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup TIM TIM + * @brief TIM HAL module driver + * @{ + */ + +#ifdef HAL_TIM_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup TIM_Private_Functions + * @{ + */ +static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); +static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); +static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource); +static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig); +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup TIM_Exported_Functions TIM Exported Functions + * @{ + */ + +/** @defgroup TIM_Exported_Functions_Group1 TIM Time Base functions + * @brief Time Base functions + * +@verbatim + ============================================================================== + ##### Time Base functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM base. + (+) De-initialize the TIM base. + (+) Start the Time Base. + (+) Stop the Time Base. + (+) Start the Time Base and enable interrupt. + (+) Stop the Time Base and disable interrupt. + (+) Start the Time Base and enable DMA transfer. + (+) Stop the Time Base and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Time base Unit according to the specified + * parameters in the TIM_HandleTypeDef and initialize the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init() + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->Base_MspInitCallback == NULL) + { + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->Base_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_TIM_Base_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Set the Time Base configuration */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM Base peripheral + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->Base_MspDeInitCallback == NULL) + { + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + } + /* DeInit the low level hardware */ + htim->Base_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_Base_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Base MSP. + * @param htim TIM Base handle + * @retval None + */ +__weak void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Base_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Base MSP. + * @param htim TIM Base handle + * @retval None + */ +__weak void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Base_MspDeInit could be implemented in the user file + */ +} + + +/** + * @brief Starts the TIM Base generation. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Check the TIM state */ + if (htim->State != HAL_TIM_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Base generation in interrupt mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Check the TIM state */ + if (htim->State != HAL_TIM_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Enable the TIM Update interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation in interrupt mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Disable the TIM Update interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_UPDATE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Base generation in DMA mode. + * @param htim TIM Base handle + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); + + /* Set the TIM state */ + if (htim->State == HAL_TIM_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->State == HAL_TIM_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + htim->State = HAL_TIM_STATE_BUSY; + } + } + else + { + return HAL_ERROR; + } + + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)pData, (uint32_t)&htim->Instance->ARR, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Update DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_UPDATE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation in DMA mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); + + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_UPDATE); + + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group2 TIM Output Compare functions + * @brief TIM Output Compare functions + * +@verbatim + ============================================================================== + ##### TIM Output Compare functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Output Compare. + (+) De-initialize the TIM Output Compare. + (+) Start the TIM Output Compare. + (+) Stop the TIM Output Compare. + (+) Start the TIM Output Compare and enable interrupt. + (+) Stop the TIM Output Compare and disable interrupt. + (+) Start the TIM Output Compare and enable DMA transfer. + (+) Stop the TIM Output Compare and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Output Compare according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_OC_DeInit() before HAL_TIM_OC_Init() + * @param htim TIM Output Compare handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->OC_MspInitCallback == NULL) + { + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->OC_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OC_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the Output Compare */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM Output Compare handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->OC_MspDeInitCallback == NULL) + { + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + } + /* DeInit the low level hardware */ + htim->OC_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OC_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Output Compare MSP. + * @param htim TIM Output Compare handle + * @retval None + */ +__weak void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Output Compare MSP. + * @param htim TIM Output Compare handle + * @retval None + */ +__weak void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Output Compare signal generation. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Output Compare signal generation. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Output Compare signal generation in interrupt mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in interrupt mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Output Compare signal generation in DMA mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in DMA mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group3 TIM PWM functions + * @brief TIM PWM functions + * +@verbatim + ============================================================================== + ##### TIM PWM functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM PWM. + (+) De-initialize the TIM PWM. + (+) Start the TIM PWM. + (+) Stop the TIM PWM. + (+) Start the TIM PWM and enable interrupt. + (+) Stop the TIM PWM and disable interrupt. + (+) Start the TIM PWM and enable DMA transfer. + (+) Stop the TIM PWM and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM PWM Time Base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init() + * @param htim TIM PWM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->PWM_MspInitCallback == NULL) + { + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->PWM_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_PWM_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the PWM */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM PWM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->PWM_MspDeInitCallback == NULL) + { + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + } + /* DeInit the low level hardware */ + htim->PWM_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_PWM_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM PWM MSP. + * @param htim TIM PWM handle + * @retval None + */ +__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM PWM MSP. + * @param htim TIM PWM handle + * @retval None + */ +__weak void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the PWM signal generation. + * @param htim TIM handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the PWM signal generation. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the PWM signal generation in interrupt mode. + * @param htim TIM PWM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the PWM signal generation in interrupt mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM PWM signal generation in DMA mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Capture/Compare 3 request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM PWM signal generation in DMA mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group4 TIM Input Capture functions + * @brief TIM Input Capture functions + * +@verbatim + ============================================================================== + ##### TIM Input Capture functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Input Capture. + (+) De-initialize the TIM Input Capture. + (+) Start the TIM Input Capture. + (+) Stop the TIM Input Capture. + (+) Start the TIM Input Capture and enable interrupt. + (+) Stop the TIM Input Capture and disable interrupt. + (+) Start the TIM Input Capture and enable DMA transfer. + (+) Stop the TIM Input Capture and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Input Capture Time base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_IC_DeInit() before HAL_TIM_IC_Init() + * @param htim TIM Input Capture handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->IC_MspInitCallback == NULL) + { + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->IC_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_IC_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the input capture */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM Input Capture handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->IC_MspDeInitCallback == NULL) + { + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + } + /* DeInit the low level hardware */ + htim->IC_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_IC_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Input Capture MSP. + * @param htim TIM Input Capture handle + * @retval None + */ +__weak void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Input Capture MSP. + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Input Capture measurement. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Input Capture measurement. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Input Capture measurement in interrupt mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Input Capture measurement in interrupt mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Input Capture measurement in DMA mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); + + /* Set the TIM channel state */ + if ((channel_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->CCR3, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->CCR4, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Input Capture measurement in DMA mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group5 TIM One Pulse functions + * @brief TIM One Pulse functions + * +@verbatim + ============================================================================== + ##### TIM One Pulse functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM One Pulse. + (+) De-initialize the TIM One Pulse. + (+) Start the TIM One Pulse. + (+) Stop the TIM One Pulse. + (+) Start the TIM One Pulse and enable interrupt. + (+) Stop the TIM One Pulse and disable interrupt. + (+) Start the TIM One Pulse and enable DMA transfer. + (+) Stop the TIM One Pulse and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM One Pulse Time Base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_OnePulse_DeInit() before HAL_TIM_OnePulse_Init() + * @note When the timer instance is initialized in One Pulse mode, timer + * channels 1 and channel 2 are reserved and cannot be used for other + * purpose. + * @param htim TIM One Pulse handle + * @param OnePulseMode Select the One pulse mode. + * This parameter can be one of the following values: + * @arg TIM_OPMODE_SINGLE: Only one pulse will be generated. + * @arg TIM_OPMODE_REPETITIVE: Repetitive pulses will be generated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_OPM_MODE(OnePulseMode)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->OnePulse_MspInitCallback == NULL) + { + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->OnePulse_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OnePulse_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Configure the Time base in the One Pulse Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Reset the OPM Bit */ + htim->Instance->CR1 &= ~TIM_CR1_OPM; + + /* Configure the OPM Mode */ + htim->Instance->CR1 |= OnePulseMode; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM One Pulse + * @param htim TIM One Pulse handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->OnePulse_MspDeInitCallback == NULL) + { + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + } + /* DeInit the low level hardware */ + htim->OnePulse_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_OnePulse_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM One Pulse MSP. + * @param htim TIM One Pulse handle + * @retval None + */ +__weak void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OnePulse_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM One Pulse MSP. + * @param htim TIM One Pulse handle + * @retval None + */ +__weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OnePulse_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM One Pulse signal generation. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together + + No need to enable the counter, it's enabled automatically by hardware + (the counter starts in response to a stimulus and generate a pulse */ + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Disable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM One Pulse signal generation in interrupt mode. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together + + No need to enable the counter, it's enabled automatically by hardware + (the counter starts in response to a stimulus and generate a pulse */ + + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation in interrupt mode. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + + /* Disable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group6 TIM Encoder functions + * @brief TIM Encoder functions + * +@verbatim + ============================================================================== + ##### TIM Encoder functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Encoder. + (+) De-initialize the TIM Encoder. + (+) Start the TIM Encoder. + (+) Stop the TIM Encoder. + (+) Start the TIM Encoder and enable interrupt. + (+) Stop the TIM Encoder and disable interrupt. + (+) Start the TIM Encoder and enable DMA transfer. + (+) Stop the TIM Encoder and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Encoder Interface and initialize the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_Encoder_DeInit() before HAL_TIM_Encoder_Init() + * @note Encoder mode and External clock mode 2 are not compatible and must not be selected together + * Ex: A call for @ref HAL_TIM_Encoder_Init will erase the settings of @ref HAL_TIM_ConfigClockSource + * using TIM_CLOCKSOURCE_ETRMODE2 and vice versa + * @note When the timer instance is initialized in Encoder mode, timer + * channels 1 and channel 2 are reserved and cannot be used for other + * purpose. + * @param htim TIM Encoder Interface handle + * @param sConfig TIM Encoder Interface configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig) +{ + uint32_t tmpsmcr; + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + assert_param(IS_TIM_ENCODER_MODE(sConfig->EncoderMode)); + assert_param(IS_TIM_IC_SELECTION(sConfig->IC1Selection)); + assert_param(IS_TIM_IC_SELECTION(sConfig->IC2Selection)); + assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC1Polarity)); + assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC2Polarity)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->Encoder_MspInitCallback == NULL) + { + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->Encoder_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_Encoder_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Reset the SMS and ECE bits */ + htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); + + /* Configure the Time base in the Encoder Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = htim->Instance->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = htim->Instance->CCER; + + /* Set the encoder Mode */ + tmpsmcr |= sConfig->EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); + tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); + + /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */ + tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC); + tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); + tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); + tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); + tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); + tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); + + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + + /* Write to TIMx CCMR1 */ + htim->Instance->CCMR1 = tmpccmr1; + + /* Write to TIMx CCER */ + htim->Instance->CCER = tmpccer; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + + +/** + * @brief DeInitializes the TIM Encoder interface + * @param htim TIM Encoder Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->Encoder_MspDeInitCallback == NULL) + { + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + } + /* DeInit the low level hardware */ + htim->Encoder_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_Encoder_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Encoder Interface MSP. + * @param htim TIM Encoder Interface handle + * @retval None + */ +__weak void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Encoder_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Encoder Interface MSP. + * @param htim TIM Encoder Interface handle + * @retval None + */ +__weak void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Encoder_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Encoder Interface. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + + /* Enable the encoder interface channels */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + break; + } + } + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + break; + } + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Encoder Interface in interrupt mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + + /* Enable the encoder interface channels */ + /* Enable the capture compare Interrupts 1 and/or 2 */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + } + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface in interrupt mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + if (Channel == TIM_CHANNEL_1) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 1 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + } + else if (Channel == TIM_CHANNEL_2) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 2 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + } + else + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 1 and 2 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Encoder Interface in DMA mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @param pData1 The destination Buffer address for IC1. + * @param pData2 The destination Buffer address for IC2. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, + uint32_t *pData2, uint16_t Length) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData1 == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_2_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData2 == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + else + { + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (channel_2_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((((pData1 == NULL) || (pData2 == NULL))) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError; + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + + default: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface in DMA mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + if (Channel == TIM_CHANNEL_1) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 1 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + } + else if (Channel == TIM_CHANNEL_2) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 2 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + } + else + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 1 and 2 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ +/** @defgroup TIM_Exported_Functions_Group7 TIM IRQ handler management + * @brief TIM IRQ handler management + * +@verbatim + ============================================================================== + ##### IRQ handler management ##### + ============================================================================== + [..] + This section provides Timer IRQ handler function. + +@endverbatim + * @{ + */ +/** + * @brief This function handles TIM interrupts requests. + * @param htim TIM handle + * @retval None + */ +void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) +{ + /* Capture compare 1 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) + { + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + } + /* Capture compare 2 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* Capture compare 3 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* Capture compare 4 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* TIM Update event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedCallback(htim); +#else + HAL_TIM_PeriodElapsedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Break input event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->BreakCallback(htim); +#else + HAL_TIMEx_BreakCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Trigger detection event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerCallback(htim); +#else + HAL_TIM_TriggerCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM commutation event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationCallback(htim); +#else + HAL_TIMEx_CommutCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions + * @brief TIM Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Configure The Input Output channels for OC, PWM, IC or One Pulse mode. + (+) Configure External Clock source. + (+) Configure Complementary channels, break features and dead time. + (+) Configure Master and the Slave synchronization. + (+) Configure the DMA Burst Mode. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIM Output Compare Channels according to the specified + * parameters in the TIM_OC_InitTypeDef. + * @param htim TIM Output Compare handle + * @param sConfig TIM Output Compare configuration structure + * @param Channel TIM Channels to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, + TIM_OC_InitTypeDef *sConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CHANNELS(Channel)); + assert_param(IS_TIM_OC_MODE(sConfig->OCMode)); + assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); + + /* Process Locked */ + __HAL_LOCK(htim); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 1 in Output Compare */ + TIM_OC1_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 2 in Output Compare */ + TIM_OC2_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 3 in Output Compare */ + TIM_OC3_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 4 in Output Compare */ + TIM_OC4_SetConfig(htim->Instance, sConfig); + break; + } + + default: + status = HAL_ERROR; + break; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM Input Capture Channels according to the specified + * parameters in the TIM_IC_InitTypeDef. + * @param htim TIM IC handle + * @param sConfig TIM Input Capture configuration structure + * @param Channel TIM Channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_IC_POLARITY(sConfig->ICPolarity)); + assert_param(IS_TIM_IC_SELECTION(sConfig->ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->ICFilter)); + + /* Process Locked */ + __HAL_LOCK(htim); + + if (Channel == TIM_CHANNEL_1) + { + /* TI1 Configuration */ + TIM_TI1_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + + /* Set the IC1PSC value */ + htim->Instance->CCMR1 |= sConfig->ICPrescaler; + } + else if (Channel == TIM_CHANNEL_2) + { + /* TI2 Configuration */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_TI2_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC2PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; + + /* Set the IC2PSC value */ + htim->Instance->CCMR1 |= (sConfig->ICPrescaler << 8U); + } + else if (Channel == TIM_CHANNEL_3) + { + /* TI3 Configuration */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + TIM_TI3_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC3PSC Bits */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC; + + /* Set the IC3PSC value */ + htim->Instance->CCMR2 |= sConfig->ICPrescaler; + } + else if (Channel == TIM_CHANNEL_4) + { + /* TI4 Configuration */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + TIM_TI4_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC4PSC Bits */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC; + + /* Set the IC4PSC value */ + htim->Instance->CCMR2 |= (sConfig->ICPrescaler << 8U); + } + else + { + status = HAL_ERROR; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM PWM channels according to the specified + * parameters in the TIM_OC_InitTypeDef. + * @param htim TIM PWM handle + * @param sConfig TIM PWM configuration structure + * @param Channel TIM Channels to be configured + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, + TIM_OC_InitTypeDef *sConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CHANNELS(Channel)); + assert_param(IS_TIM_PWM_MODE(sConfig->OCMode)); + assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); + assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode)); + + /* Process Locked */ + __HAL_LOCK(htim); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Configure the Channel 1 in PWM mode */ + TIM_OC1_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel1 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; + htim->Instance->CCMR1 |= sConfig->OCFastMode; + break; + } + + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Configure the Channel 2 in PWM mode */ + TIM_OC2_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel2 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; + htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Configure the Channel 3 in PWM mode */ + TIM_OC3_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel3 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; + htim->Instance->CCMR2 |= sConfig->OCFastMode; + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Configure the Channel 4 in PWM mode */ + TIM_OC4_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel4 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; + htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; + break; + } + + default: + status = HAL_ERROR; + break; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM One Pulse Channels according to the specified + * parameters in the TIM_OnePulse_InitTypeDef. + * @param htim TIM One Pulse handle + * @param sConfig TIM One Pulse configuration structure + * @param OutputChannel TIM output channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @param InputChannel TIM input Channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @note To output a waveform with a minimum delay user can enable the fast + * mode by calling the @ref __HAL_TIM_ENABLE_OCxFAST macro. Then CCx + * output is forced in response to the edge detection on TIx input, + * without taking in account the comparison. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, + uint32_t OutputChannel, uint32_t InputChannel) +{ + HAL_StatusTypeDef status = HAL_OK; + TIM_OC_InitTypeDef temp1; + + /* Check the parameters */ + assert_param(IS_TIM_OPM_CHANNELS(OutputChannel)); + assert_param(IS_TIM_OPM_CHANNELS(InputChannel)); + + if (OutputChannel != InputChannel) + { + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Extract the Output compare configuration from sConfig structure */ + temp1.OCMode = sConfig->OCMode; + temp1.Pulse = sConfig->Pulse; + temp1.OCPolarity = sConfig->OCPolarity; + temp1.OCNPolarity = sConfig->OCNPolarity; + temp1.OCIdleState = sConfig->OCIdleState; + temp1.OCNIdleState = sConfig->OCNIdleState; + + switch (OutputChannel) + { + case TIM_CHANNEL_1: + { + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + TIM_OC1_SetConfig(htim->Instance, &temp1); + break; + } + + case TIM_CHANNEL_2: + { + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_OC2_SetConfig(htim->Instance, &temp1); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + switch (InputChannel) + { + case TIM_CHANNEL_1: + { + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + TIM_TI1_SetConfig(htim->Instance, sConfig->ICPolarity, + sConfig->ICSelection, sConfig->ICFilter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + + /* Select the Trigger source */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI1FP1; + + /* Select the Slave Mode */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; + break; + } + + case TIM_CHANNEL_2: + { + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_TI2_SetConfig(htim->Instance, sConfig->ICPolarity, + sConfig->ICSelection, sConfig->ICFilter); + + /* Reset the IC2PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; + + /* Select the Trigger source */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI2FP2; + + /* Select the Slave Mode */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; + break; + } + + default: + status = HAL_ERROR; + break; + } + } + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Configure the DMA Burst to transfer Data from the memory to the TIM peripheral + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source + * @param BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @note This function should be used only when BurstLength is equal to DMA data transfer length. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) +{ + HAL_StatusTypeDef status; + + status = HAL_TIM_DMABurst_MultiWriteStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, + ((BurstLength) >> 8U) + 1U); + + + + return status; +} + +/** + * @brief Configure the DMA Burst to transfer multiple Data from the memory to the TIM peripheral + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source + * @param BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @param DataLength Data length. This parameter can be one value + * between 1 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + assert_param(IS_TIM_DMA_LENGTH(BurstLength)); + assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); + + if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) + { + if ((BurstBuffer == NULL) && (BurstLength > 0U)) + { + return HAL_ERROR; + } + else + { + htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; + } + } + else + { + /* nothing to do */ + } + + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_COM: + { + /* Set the DMA commutation callbacks */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_TRIGGER: + { + /* Set the DMA trigger callbacks */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; + htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Configure the DMA Burst Mode */ + htim->Instance->DCR = (BurstBaseAddress | BurstLength); + /* Enable the TIM DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM DMA Burst mode + * @param htim TIM handle + * @param BurstRequestSrc TIM DMA Request sources to disable + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + + /* Abort the DMA transfer (at least disable the DMA stream) */ + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + break; + } + case TIM_DMA_CC1: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + case TIM_DMA_CC2: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + case TIM_DMA_CC3: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + case TIM_DMA_CC4: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + case TIM_DMA_COM: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); + break; + } + case TIM_DMA_TRIGGER: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + } + + /* Return function status */ + return status; +} + +/** + * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source + * @param BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @note This function should be used only when BurstLength is equal to DMA data transfer length. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) +{ + HAL_StatusTypeDef status; + + status = HAL_TIM_DMABurst_MultiReadStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, + ((BurstLength) >> 8U) + 1U); + + + return status; +} + +/** + * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one of the following values: + * @arg TIM_DMA_UPDATE: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source + * @param BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @param DataLength Data length. This parameter can be one value + * between 1 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + assert_param(IS_TIM_DMA_LENGTH(BurstLength)); + assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); + + if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) + { + if ((BurstBuffer == NULL) && (BurstLength > 0U)) + { + return HAL_ERROR; + } + else + { + htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; + } + } + else + { + /* nothing to do */ + } + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC3: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC4: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_COM: + { + /* Set the DMA commutation callbacks */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_TRIGGER: + { + /* Set the DMA trigger callbacks */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; + htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Configure the DMA Burst Mode */ + htim->Instance->DCR = (BurstBaseAddress | BurstLength); + + /* Enable the TIM DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stop the DMA burst reading + * @param htim TIM handle + * @param BurstRequestSrc TIM DMA Request sources to disable. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + + /* Abort the DMA transfer (at least disable the DMA stream) */ + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + break; + } + case TIM_DMA_CC1: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + case TIM_DMA_CC2: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + case TIM_DMA_CC3: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + case TIM_DMA_CC4: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + case TIM_DMA_COM: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); + break; + } + case TIM_DMA_TRIGGER: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + } + + /* Return function status */ + return status; +} + +/** + * @brief Generate a software event + * @param htim TIM handle + * @param EventSource specifies the event source. + * This parameter can be one of the following values: + * @arg TIM_EVENTSOURCE_UPDATE: Timer update Event source + * @arg TIM_EVENTSOURCE_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EVENTSOURCE_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EVENTSOURCE_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EVENTSOURCE_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EVENTSOURCE_COM: Timer COM event source + * @arg TIM_EVENTSOURCE_TRIGGER: Timer Trigger Event source + * @arg TIM_EVENTSOURCE_BREAK: Timer Break event source + * @note Basic timers can only generate an update event. + * @note TIM_EVENTSOURCE_COM is relevant only with advanced timer instances. + * @note TIM_EVENTSOURCE_BREAK are relevant only for timer instances + * supporting a break input. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_EVENT_SOURCE(EventSource)); + + /* Process Locked */ + __HAL_LOCK(htim); + + /* Change the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Set the event sources */ + htim->Instance->EGR = EventSource; + + /* Change the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the OCRef clear feature + * @param htim TIM handle + * @param sClearInputConfig pointer to a TIM_ClearInputConfigTypeDef structure that + * contains the OCREF clear feature and parameters for the TIM peripheral. + * @param Channel specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 + * @arg TIM_CHANNEL_2: TIM Channel 2 + * @arg TIM_CHANNEL_3: TIM Channel 3 + * @arg TIM_CHANNEL_4: TIM Channel 4 + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, + TIM_ClearInputConfigTypeDef *sClearInputConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_OCXREF_CLEAR_INSTANCE(htim->Instance)); + assert_param(IS_TIM_CLEARINPUT_SOURCE(sClearInputConfig->ClearInputSource)); + + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + switch (sClearInputConfig->ClearInputSource) + { + case TIM_CLEARINPUTSOURCE_NONE: + { + /* Clear the OCREF clear selection bit and the the ETR Bits */ + CLEAR_BIT(htim->Instance->SMCR, (TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP)); + break; + } + + case TIM_CLEARINPUTSOURCE_ETR: + { + /* Check the parameters */ + assert_param(IS_TIM_CLEARINPUT_POLARITY(sClearInputConfig->ClearInputPolarity)); + assert_param(IS_TIM_CLEARINPUT_PRESCALER(sClearInputConfig->ClearInputPrescaler)); + assert_param(IS_TIM_CLEARINPUT_FILTER(sClearInputConfig->ClearInputFilter)); + + /* When OCRef clear feature is used with ETR source, ETR prescaler must be off */ + if (sClearInputConfig->ClearInputPrescaler != TIM_CLEARINPUTPRESCALER_DIV1) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + TIM_ETR_SetConfig(htim->Instance, + sClearInputConfig->ClearInputPrescaler, + sClearInputConfig->ClearInputPolarity, + sClearInputConfig->ClearInputFilter); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + switch (Channel) + { + case TIM_CHANNEL_1: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 1 */ + SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); + } + else + { + /* Disable the OCREF clear feature for Channel 1 */ + CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); + } + break; + } + case TIM_CHANNEL_2: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 2 */ + SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); + } + else + { + /* Disable the OCREF clear feature for Channel 2 */ + CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); + } + break; + } + case TIM_CHANNEL_3: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 3 */ + SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); + } + else + { + /* Disable the OCREF clear feature for Channel 3 */ + CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); + } + break; + } + case TIM_CHANNEL_4: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 4 */ + SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); + } + else + { + /* Disable the OCREF clear feature for Channel 4 */ + CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); + } + break; + } + default: + break; + } + } + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Configures the clock source to be used + * @param htim TIM handle + * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that + * contains the clock source information for the TIM peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Check the parameters */ + assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource)); + + /* Reset the SMS, TS, ECE, ETPS and ETRF bits */ + tmpsmcr = htim->Instance->SMCR; + tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + htim->Instance->SMCR = tmpsmcr; + + switch (sClockSourceConfig->ClockSource) + { + case TIM_CLOCKSOURCE_INTERNAL: + { + assert_param(IS_TIM_INSTANCE(htim->Instance)); + break; + } + + case TIM_CLOCKSOURCE_ETRMODE1: + { + /* Check whether or not the timer instance supports external trigger input mode 1 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); + + /* Check ETR input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + /* Configure the ETR Clock source */ + TIM_ETR_SetConfig(htim->Instance, + sClockSourceConfig->ClockPrescaler, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + + /* Select the External clock mode1 and the ETRF trigger */ + tmpsmcr = htim->Instance->SMCR; + tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + break; + } + + case TIM_CLOCKSOURCE_ETRMODE2: + { + /* Check whether or not the timer instance supports external trigger input mode 2 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(htim->Instance)); + + /* Check ETR input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + /* Configure the ETR Clock source */ + TIM_ETR_SetConfig(htim->Instance, + sClockSourceConfig->ClockPrescaler, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + /* Enable the External clock mode2 */ + htim->Instance->SMCR |= TIM_SMCR_ECE; + break; + } + + case TIM_CLOCKSOURCE_TI1: + { + /* Check whether or not the timer instance supports external clock mode 1 */ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI1 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI1_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); + break; + } + + case TIM_CLOCKSOURCE_TI2: + { + /* Check whether or not the timer instance supports external clock mode 1 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI2 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI2_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); + break; + } + + case TIM_CLOCKSOURCE_TI1ED: + { + /* Check whether or not the timer instance supports external clock mode 1 */ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI1 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI1_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); + break; + } + + case TIM_CLOCKSOURCE_ITR0: + case TIM_CLOCKSOURCE_ITR1: + case TIM_CLOCKSOURCE_ITR2: + case TIM_CLOCKSOURCE_ITR3: + { + /* Check whether or not the timer instance supports internal trigger input */ + assert_param(IS_TIM_CLOCKSOURCE_ITRX_INSTANCE(htim->Instance)); + + TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); + break; + } + + default: + status = HAL_ERROR; + break; + } + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Selects the signal connected to the TI1 input: direct from CH1_input + * or a XOR combination between CH1_input, CH2_input & CH3_input + * @param htim TIM handle. + * @param TI1_Selection Indicate whether or not channel 1 is connected to the + * output of a XOR gate. + * This parameter can be one of the following values: + * @arg TIM_TI1SELECTION_CH1: The TIMx_CH1 pin is connected to TI1 input + * @arg TIM_TI1SELECTION_XORCOMBINATION: The TIMx_CH1, CH2 and CH3 + * pins are connected to the TI1 input (XOR combination) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection) +{ + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_XOR_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TI1SELECTION(TI1_Selection)); + + /* Get the TIMx CR2 register value */ + tmpcr2 = htim->Instance->CR2; + + /* Reset the TI1 selection */ + tmpcr2 &= ~TIM_CR2_TI1S; + + /* Set the TI1 selection */ + tmpcr2 |= TI1_Selection; + + /* Write to TIMxCR2 */ + htim->Instance->CR2 = tmpcr2; + + return HAL_OK; +} + +/** + * @brief Configures the TIM in Slave mode + * @param htim TIM handle. + * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that + * contains the selected trigger (internal trigger input, filtered + * timer input or external trigger input) and the Slave mode + * (Disable, Reset, Gated, Trigger, External clock mode 1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + /* Check the parameters */ + assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); + assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); + + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + /* Disable Trigger Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_TRIGGER); + + /* Disable Trigger DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIM in Slave mode in interrupt mode + * @param htim TIM handle. + * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that + * contains the selected trigger (internal trigger input, filtered + * timer input or external trigger input) and the Slave mode + * (Disable, Reset, Gated, Trigger, External clock mode 1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + /* Check the parameters */ + assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); + assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); + + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + /* Enable Trigger Interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_TRIGGER); + + /* Disable Trigger DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Read the captured value from Capture Compare unit + * @param htim TIM handle. + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval Captured value + */ +uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpreg = 0U; + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Return the capture 1 value */ + tmpreg = htim->Instance->CCR1; + + break; + } + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Return the capture 2 value */ + tmpreg = htim->Instance->CCR2; + + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Return the capture 3 value */ + tmpreg = htim->Instance->CCR3; + + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Return the capture 4 value */ + tmpreg = htim->Instance->CCR4; + + break; + } + + default: + break; + } + + return tmpreg; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions + * @brief TIM Callbacks functions + * +@verbatim + ============================================================================== + ##### TIM Callbacks functions ##### + ============================================================================== + [..] + This section provides TIM callback functions: + (+) TIM Period elapsed callback + (+) TIM Output Compare callback + (+) TIM Input capture callback + (+) TIM Trigger callback + (+) TIM Error callback + +@endverbatim + * @{ + */ + +/** + * @brief Period elapsed callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PeriodElapsedCallback could be implemented in the user file + */ +} + +/** + * @brief Period elapsed half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PeriodElapsedHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Output Compare callback in non-blocking mode + * @param htim TIM OC handle + * @retval None + */ +__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file + */ +} + +/** + * @brief Input Capture callback in non-blocking mode + * @param htim TIM IC handle + * @retval None + */ +__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_CaptureCallback could be implemented in the user file + */ +} + +/** + * @brief Input Capture half complete callback in non-blocking mode + * @param htim TIM IC handle + * @retval None + */ +__weak void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_CaptureHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief PWM Pulse finished callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file + */ +} + +/** + * @brief PWM Pulse finished half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_PulseFinishedHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Trigger detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_TriggerCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Trigger detection half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_TriggerHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Timer error callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_ErrorCallback could be implemented in the user file + */ +} + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User TIM callback to be used instead of the weak predefined callback + * @param htim tim handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID + * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID + * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID + * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID + * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID + * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID + * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID + * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID + * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID + * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID + * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID + * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID + * @param pCallback pointer to the callback function + * @retval status + */ +HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, + pTIM_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(htim); + + if (htim->State == HAL_TIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + htim->Base_MspInitCallback = pCallback; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + htim->Base_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + htim->IC_MspInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + htim->IC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + htim->OC_MspInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + htim->OC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + htim->PWM_MspInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + htim->PWM_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + htim->OnePulse_MspInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + htim->OnePulse_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + htim->Encoder_MspInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + htim->Encoder_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + htim->HallSensor_MspInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + htim->HallSensor_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_CB_ID : + htim->PeriodElapsedCallback = pCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : + htim->PeriodElapsedHalfCpltCallback = pCallback; + break; + + case HAL_TIM_TRIGGER_CB_ID : + htim->TriggerCallback = pCallback; + break; + + case HAL_TIM_TRIGGER_HALF_CB_ID : + htim->TriggerHalfCpltCallback = pCallback; + break; + + case HAL_TIM_IC_CAPTURE_CB_ID : + htim->IC_CaptureCallback = pCallback; + break; + + case HAL_TIM_IC_CAPTURE_HALF_CB_ID : + htim->IC_CaptureHalfCpltCallback = pCallback; + break; + + case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : + htim->OC_DelayElapsedCallback = pCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : + htim->PWM_PulseFinishedCallback = pCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : + htim->PWM_PulseFinishedHalfCpltCallback = pCallback; + break; + + case HAL_TIM_ERROR_CB_ID : + htim->ErrorCallback = pCallback; + break; + + case HAL_TIM_COMMUTATION_CB_ID : + htim->CommutationCallback = pCallback; + break; + + case HAL_TIM_COMMUTATION_HALF_CB_ID : + htim->CommutationHalfCpltCallback = pCallback; + break; + + case HAL_TIM_BREAK_CB_ID : + htim->BreakCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (htim->State == HAL_TIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + htim->Base_MspInitCallback = pCallback; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + htim->Base_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + htim->IC_MspInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + htim->IC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + htim->OC_MspInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + htim->OC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + htim->PWM_MspInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + htim->PWM_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + htim->OnePulse_MspInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + htim->OnePulse_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + htim->Encoder_MspInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + htim->Encoder_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + htim->HallSensor_MspInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + htim->HallSensor_MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Unregister a TIM callback + * TIM callback is redirected to the weak predefined callback + * @param htim tim handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID + * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID + * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID + * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID + * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID + * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID + * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID + * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID + * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID + * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID + * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID + * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(htim); + + if (htim->State == HAL_TIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + /* Legacy weak Base MspInit Callback */ + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + /* Legacy weak Base Msp DeInit Callback */ + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + /* Legacy weak IC Msp Init Callback */ + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + /* Legacy weak IC Msp DeInit Callback */ + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + /* Legacy weak OC Msp Init Callback */ + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + /* Legacy weak OC Msp DeInit Callback */ + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + /* Legacy weak PWM Msp Init Callback */ + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + /* Legacy weak PWM Msp DeInit Callback */ + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + /* Legacy weak One Pulse Msp Init Callback */ + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + /* Legacy weak One Pulse Msp DeInit Callback */ + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + /* Legacy weak Encoder Msp Init Callback */ + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + /* Legacy weak Encoder Msp DeInit Callback */ + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + /* Legacy weak Hall Sensor Msp Init Callback */ + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + /* Legacy weak Hall Sensor Msp DeInit Callback */ + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + break; + + case HAL_TIM_PERIOD_ELAPSED_CB_ID : + /* Legacy weak Period Elapsed Callback */ + htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : + /* Legacy weak Period Elapsed half complete Callback */ + htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; + break; + + case HAL_TIM_TRIGGER_CB_ID : + /* Legacy weak Trigger Callback */ + htim->TriggerCallback = HAL_TIM_TriggerCallback; + break; + + case HAL_TIM_TRIGGER_HALF_CB_ID : + /* Legacy weak Trigger half complete Callback */ + htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; + break; + + case HAL_TIM_IC_CAPTURE_CB_ID : + /* Legacy weak IC Capture Callback */ + htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; + break; + + case HAL_TIM_IC_CAPTURE_HALF_CB_ID : + /* Legacy weak IC Capture half complete Callback */ + htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; + break; + + case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : + /* Legacy weak OC Delay Elapsed Callback */ + htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : + /* Legacy weak PWM Pulse Finished Callback */ + htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : + /* Legacy weak PWM Pulse Finished half complete Callback */ + htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; + break; + + case HAL_TIM_ERROR_CB_ID : + /* Legacy weak Error Callback */ + htim->ErrorCallback = HAL_TIM_ErrorCallback; + break; + + case HAL_TIM_COMMUTATION_CB_ID : + /* Legacy weak Commutation Callback */ + htim->CommutationCallback = HAL_TIMEx_CommutCallback; + break; + + case HAL_TIM_COMMUTATION_HALF_CB_ID : + /* Legacy weak Commutation half complete Callback */ + htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; + break; + + case HAL_TIM_BREAK_CB_ID : + /* Legacy weak Break Callback */ + htim->BreakCallback = HAL_TIMEx_BreakCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (htim->State == HAL_TIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + /* Legacy weak Base MspInit Callback */ + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + /* Legacy weak Base Msp DeInit Callback */ + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + /* Legacy weak IC Msp Init Callback */ + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + /* Legacy weak IC Msp DeInit Callback */ + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + /* Legacy weak OC Msp Init Callback */ + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + /* Legacy weak OC Msp DeInit Callback */ + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + /* Legacy weak PWM Msp Init Callback */ + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + /* Legacy weak PWM Msp DeInit Callback */ + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + /* Legacy weak One Pulse Msp Init Callback */ + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + /* Legacy weak One Pulse Msp DeInit Callback */ + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + /* Legacy weak Encoder Msp Init Callback */ + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + /* Legacy weak Encoder Msp DeInit Callback */ + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + /* Legacy weak Hall Sensor Msp Init Callback */ + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + /* Legacy weak Hall Sensor Msp DeInit Callback */ + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return status; +} +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions + * @brief TIM Peripheral State functions + * +@verbatim + ============================================================================== + ##### Peripheral State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the TIM Base handle state. + * @param htim TIM Base handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM OC handle state. + * @param htim TIM Output Compare handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM PWM handle state. + * @param htim TIM handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Input Capture handle state. + * @param htim TIM IC handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM One Pulse Mode handle state. + * @param htim TIM OPM handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Encoder Mode handle state. + * @param htim TIM Encoder Interface handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Encoder Mode handle state. + * @param htim TIM handle + * @retval Active channel + */ +HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim) +{ + return htim->Channel; +} + +/** + * @brief Return actual state of the TIM channel. + * @param htim TIM handle + * @param Channel TIM Channel + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 + * @arg TIM_CHANNEL_2: TIM Channel 2 + * @arg TIM_CHANNEL_3: TIM Channel 3 + * @arg TIM_CHANNEL_4: TIM Channel 4 + * @arg TIM_CHANNEL_5: TIM Channel 5 + * @arg TIM_CHANNEL_6: TIM Channel 6 + * @retval TIM Channel state + */ +HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_state; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + + return channel_state; +} + +/** + * @brief Return actual state of a DMA burst operation. + * @param htim TIM handle + * @retval DMA burst state + */ +HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + + return htim->DMABurstState; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Functions TIM Private Functions + * @{ + */ + +/** + * @brief TIM DMA error callback + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMAError(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->ErrorCallback(htim); +#else + HAL_TIM_ErrorCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Delay Pulse complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Delay Pulse half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedHalfCpltCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Capture complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Capture half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureHalfCpltCallback(htim); +#else + HAL_TIM_IC_CaptureHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Period Elapse complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (htim->hdma[TIM_DMA_ID_UPDATE]->Init.Mode == DMA_NORMAL) + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedCallback(htim); +#else + HAL_TIM_PeriodElapsedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Period Elapse half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedHalfCpltCallback(htim); +#else + HAL_TIM_PeriodElapsedHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Trigger callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (htim->hdma[TIM_DMA_ID_TRIGGER]->Init.Mode == DMA_NORMAL) + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerCallback(htim); +#else + HAL_TIM_TriggerCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Trigger half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerHalfCpltCallback(htim); +#else + HAL_TIM_TriggerHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief Time Base configuration + * @param TIMx TIM peripheral + * @param Structure TIM Base configuration structure + * @retval None + */ +void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) +{ + uint32_t tmpcr1; + tmpcr1 = TIMx->CR1; + + /* Set TIM Time Base Unit parameters ---------------------------------------*/ + if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) + { + /* Select the Counter Mode */ + tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); + tmpcr1 |= Structure->CounterMode; + } + + if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) + { + /* Set the clock division */ + tmpcr1 &= ~TIM_CR1_CKD; + tmpcr1 |= (uint32_t)Structure->ClockDivision; + } + + /* Set the auto-reload preload */ + MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = (uint32_t)Structure->Period ; + + /* Set the Prescaler value */ + TIMx->PSC = Structure->Prescaler; + + if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = Structure->RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler + and the repetition counter (only for advanced timer) value immediately */ + TIMx->EGR = TIM_EGR_UG; +} + +/** + * @brief Timer Output Compare 1 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= ~TIM_CCER_CC1E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= ~TIM_CCMR1_OC1M; + tmpccmrx &= ~TIM_CCMR1_CC1S; + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC1P; + /* Set the Output Compare Polarity */ + tmpccer |= OC_Config->OCPolarity; + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) + { + /* Check parameters */ + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC1NP; + /* Set the Output N Polarity */ + tmpccer |= OC_Config->OCNPolarity; + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC1NE; + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS1; + tmpcr2 &= ~TIM_CR2_OIS1N; + /* Set the Output Idle state */ + tmpcr2 |= OC_Config->OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= OC_Config->OCNIdleState; + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 2 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR1_OC2M; + tmpccmrx &= ~TIM_CCMR1_CC2S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC2P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 4U); + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC2NP; + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 4U); + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC2NE; + + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS2; + tmpcr2 &= ~TIM_CR2_OIS2N; + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 2U); + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 2U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 3 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 3: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC3E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR2_OC3M; + tmpccmrx &= ~TIM_CCMR2_CC3S; + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC3P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 8U); + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC3NP; + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 8U); + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC3NE; + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS3; + tmpcr2 &= ~TIM_CR2_OIS3N; + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 4U); + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 4U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 4 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= ~TIM_CCER_CC4E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR2_OC4M; + tmpccmrx &= ~TIM_CCMR2_CC4S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC4P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 12U); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS4; + + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 6U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Slave Timer configuration function + * @param htim TIM handle + * @param sSlaveConfig Slave timer configuration + * @retval None + */ +static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Reset the Trigger Selection Bits */ + tmpsmcr &= ~TIM_SMCR_TS; + /* Set the Input Trigger source */ + tmpsmcr |= sSlaveConfig->InputTrigger; + + /* Reset the slave mode Bits */ + tmpsmcr &= ~TIM_SMCR_SMS; + /* Set the slave mode */ + tmpsmcr |= sSlaveConfig->SlaveMode; + + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + + /* Configure the trigger prescaler, filter, and polarity */ + switch (sSlaveConfig->InputTrigger) + { + case TIM_TS_ETRF: + { + /* Check the parameters */ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPRESCALER(sSlaveConfig->TriggerPrescaler)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + /* Configure the ETR Trigger source */ + TIM_ETR_SetConfig(htim->Instance, + sSlaveConfig->TriggerPrescaler, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_TI1F_ED: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + if (sSlaveConfig->SlaveMode == TIM_SLAVEMODE_GATED) + { + return HAL_ERROR; + } + + /* Disable the Channel 1: Reset the CC1E Bit */ + tmpccer = htim->Instance->CCER; + htim->Instance->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = htim->Instance->CCMR1; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= ((sSlaveConfig->TriggerFilter) << 4U); + + /* Write to TIMx CCMR1 and CCER registers */ + htim->Instance->CCMR1 = tmpccmr1; + htim->Instance->CCER = tmpccer; + break; + } + + case TIM_TS_TI1FP1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + /* Configure TI1 Filter and Polarity */ + TIM_TI1_ConfigInputStage(htim->Instance, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_TI2FP2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + /* Configure TI2 Filter and Polarity */ + TIM_TI2_ConfigInputStage(htim->Instance, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_ITR0: + case TIM_TS_ITR1: + case TIM_TS_ITR2: + case TIM_TS_ITR3: + { + /* Check the parameter */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + break; + } + + default: + status = HAL_ERROR; + break; + } + + return status; +} + +/** + * @brief Configure the TI1 as Input. + * @param TIMx to select the TIM peripheral. + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICSelection specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSELECTION_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI2FP1 + * (on channel2 path) is used as the input signal. Therefore CCMR1 must be + * protected against un-initialized filter and polarity values. + */ +void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input */ + if (IS_TIM_CC2_INSTANCE(TIMx) != RESET) + { + tmpccmr1 &= ~TIM_CCMR1_CC1S; + tmpccmr1 |= TIM_ICSelection; + } + else + { + tmpccmr1 |= TIM_CCMR1_CC1S_0; + } + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= ((TIM_ICFilter << 4U) & TIM_CCMR1_IC1F); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= (TIM_ICPolarity & (TIM_CCER_CC1P | TIM_CCER_CC1NP)); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the Polarity and Filter for TI1. + * @param TIMx to select the TIM peripheral. + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 1: Reset the CC1E Bit */ + tmpccer = TIMx->CCER; + TIMx->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= (TIM_ICFilter << 4U); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= TIM_ICPolarity; + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx to select the TIM peripheral + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICSelection specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSELECTION_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI1FP2 + * (on channel1 path) is used as the input signal. Therefore CCMR1 must be + * protected against un-initialized filter and polarity values. + */ +static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr1 &= ~TIM_CCMR1_CC2S; + tmpccmr1 |= (TIM_ICSelection << 8U); + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC2F; + tmpccmr1 |= ((TIM_ICFilter << 12U) & TIM_CCMR1_IC2F); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= ((TIM_ICPolarity << 4U) & (TIM_CCER_CC2P | TIM_CCER_CC2NP)); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the Polarity and Filter for TI2. + * @param TIMx to select the TIM peripheral. + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC2F; + tmpccmr1 |= (TIM_ICFilter << 12U); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (TIM_ICPolarity << 4U); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx to select the TIM peripheral + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICSelection specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSELECTION_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI3FP4 + * (on channel1 path) is used as the input signal. Therefore CCMR2 must be + * protected against un-initialized filter and polarity values. + */ +static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= ~TIM_CCER_CC3E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr2 &= ~TIM_CCMR2_CC3S; + tmpccmr2 |= TIM_ICSelection; + + /* Set the filter */ + tmpccmr2 &= ~TIM_CCMR2_IC3F; + tmpccmr2 |= ((TIM_ICFilter << 4U) & TIM_CCMR2_IC3F); + + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP); + tmpccer |= ((TIM_ICPolarity << 8U) & (TIM_CCER_CC3P | TIM_CCER_CC3NP)); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx to select the TIM peripheral + * @param TIM_ICPolarity The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPOLARITY_RISING + * @arg TIM_ICPOLARITY_FALLING + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICSelection specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSELECTION_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI4FP3 + * (on channel1 path) is used as the input signal. Therefore CCMR2 must be + * protected against un-initialized filter and polarity values. + * @retval None + */ +static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= ~TIM_CCER_CC4E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr2 &= ~TIM_CCMR2_CC4S; + tmpccmr2 |= (TIM_ICSelection << 8U); + + /* Set the filter */ + tmpccmr2 &= ~TIM_CCMR2_IC4F; + tmpccmr2 |= ((TIM_ICFilter << 12U) & TIM_CCMR2_IC4F); + + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP); + tmpccer |= ((TIM_ICPolarity << 12U) & (TIM_CCER_CC4P | TIM_CCER_CC4NP)); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer ; +} + +/** + * @brief Selects the Input Trigger source + * @param TIMx to select the TIM peripheral + * @param InputTriggerSource The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource) +{ + uint32_t tmpsmcr; + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the TS Bits */ + tmpsmcr &= ~TIM_SMCR_TS; + /* Set the Input Trigger source and the slave mode*/ + tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx to select the TIM peripheral + * @param TIM_ExtTRGPrescaler The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ETRPRESCALER_DIV1: ETRP Prescaler OFF. + * @arg TIM_ETRPRESCALER_DIV2: ETRP frequency divided by 2. + * @arg TIM_ETRPRESCALER_DIV4: ETRP frequency divided by 4. + * @arg TIM_ETRPRESCALER_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ETRPOLARITY_INVERTED: active low or falling edge active. + * @arg TIM_ETRPOLARITY_NONINVERTED: active high or rising edge active. + * @param ExtTRGFilter External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, + uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter) +{ + uint32_t tmpsmcr; + + tmpsmcr = TIMx->SMCR; + + /* Reset the ETR Bits */ + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx to select the TIM peripheral + * @param Channel specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 + * @arg TIM_CHANNEL_2: TIM Channel 2 + * @arg TIM_CHANNEL_3: TIM Channel 3 + * @arg TIM_CHANNEL_4: TIM Channel 4 + * @param ChannelState specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE. + * @retval None + */ +void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState) +{ + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(TIMx)); + assert_param(IS_TIM_CHANNELS(Channel)); + + tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ + + /* Reset the CCxE Bit */ + TIMx->CCER &= ~tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ +} + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +/** + * @brief Reset interrupt callbacks to the legacy weak callbacks. + * @param htim pointer to a TIM_HandleTypeDef structure that contains + * the configuration information for TIM module. + * @retval None + */ +void TIM_ResetCallback(TIM_HandleTypeDef *htim) +{ + /* Reset the TIM callback to the legacy weak callbacks */ + htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; + htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; + htim->TriggerCallback = HAL_TIM_TriggerCallback; + htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; + htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; + htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; + htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; + htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; + htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; + htim->ErrorCallback = HAL_TIM_ErrorCallback; + htim->CommutationCallback = HAL_TIMEx_CommutCallback; + htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; + htim->BreakCallback = HAL_TIMEx_BreakCallback; +} +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +#endif /* HAL_TIM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c index 092175f..1b59f15 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c @@ -1,2428 +1,2428 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim_ex.c - * @author MCD Application Team - * @brief TIM HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Timer Extended peripheral: - * + Time Hall Sensor Interface Initialization - * + Time Hall Sensor Interface Start - * + Time Complementary signal break and dead time configuration - * + Time Master and Slave synchronization configuration - * + Timer remapping capabilities configuration - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### TIMER Extended features ##### - ============================================================================== - [..] - The Timer Extended features include: - (#) Complementary outputs with programmable dead-time for : - (++) Output Compare - (++) PWM generation (Edge and Center-aligned Mode) - (++) One-pulse mode output - (#) Synchronization circuit to control the timer with external signals and to - interconnect several timers together. - (#) Break input to put the timer output signals in reset state or in a known state. - (#) Supports incremental (quadrature) encoder and hall-sensor circuitry for - positioning purposes - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the TIM low level resources by implementing the following functions - depending on the selected feature: - (++) Hall Sensor output : HAL_TIMEx_HallSensor_MspInit() - - (#) Initialize the TIM low level resources : - (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); - (##) TIM pins configuration - (+++) Enable the clock for the TIM GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); - - (#) The external Clock can be configured, if needed (the default clock is the - internal clock from the APBx), using the following function: - HAL_TIM_ConfigClockSource, the clock configuration should be done before - any start function. - - (#) Configure the TIM in the desired functioning mode using one of the - initialization function of this driver: - (++) HAL_TIMEx_HallSensor_Init() and HAL_TIMEx_ConfigCommutEvent(): to use the - Timer Hall Sensor Interface and the commutation event with the corresponding - Interrupt and DMA request if needed (Note that One Timer is used to interface - with the Hall sensor Interface and another Timer should be used to use - the commutation event). - - (#) Activate the TIM peripheral using one of the start functions: - (++) Complementary Output Compare : HAL_TIMEx_OCN_Start(), HAL_TIMEx_OCN_Start_DMA(), - HAL_TIMEx_OCN_Start_IT() - (++) Complementary PWM generation : HAL_TIMEx_PWMN_Start(), HAL_TIMEx_PWMN_Start_DMA(), - HAL_TIMEx_PWMN_Start_IT() - (++) Complementary One-pulse mode output : HAL_TIMEx_OnePulseN_Start(), HAL_TIMEx_OnePulseN_Start_IT() - (++) Hall Sensor output : HAL_TIMEx_HallSensor_Start(), HAL_TIMEx_HallSensor_Start_DMA(), - HAL_TIMEx_HallSensor_Start_IT(). - - @endverbatim - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup TIMEx TIMEx - * @brief TIM Extended HAL module driver - * @{ - */ - -#ifdef HAL_TIM_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma); -static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState); - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Functions TIM Extended Exported Functions - * @{ - */ - -/** @defgroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions - * @brief Timer Hall Sensor functions - * -@verbatim - ============================================================================== - ##### Timer Hall Sensor functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure TIM HAL Sensor. - (+) De-initialize TIM HAL Sensor. - (+) Start the Hall Sensor Interface. - (+) Stop the Hall Sensor Interface. - (+) Start the Hall Sensor Interface and enable interrupts. - (+) Stop the Hall Sensor Interface and disable interrupts. - (+) Start the Hall Sensor Interface and enable DMA transfers. - (+) Stop the Hall Sensor Interface and disable DMA transfers. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Hall Sensor Interface and initialize the associated handle. - * @note When the timer instance is initialized in Hall Sensor Interface mode, - * timer channels 1 and channel 2 are reserved and cannot be used for - * other purpose. - * @param htim TIM Hall Sensor Interface handle - * @param sConfig TIM Hall Sensor configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig) -{ - TIM_OC_InitTypeDef OC_Config; - - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - assert_param(IS_TIM_IC_POLARITY(sConfig->IC1Polarity)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy week callbacks */ - TIM_ResetCallback(htim); - - if (htim->HallSensor_MspInitCallback == NULL) - { - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->HallSensor_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIMEx_HallSensor_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Configure the Time base in the Encoder Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Configure the Channel 1 as Input Channel to interface with the three Outputs of the Hall sensor */ - TIM_TI1_SetConfig(htim->Instance, sConfig->IC1Polarity, TIM_ICSELECTION_TRC, sConfig->IC1Filter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - /* Set the IC1PSC value */ - htim->Instance->CCMR1 |= sConfig->IC1Prescaler; - - /* Enable the Hall sensor interface (XOR function of the three inputs) */ - htim->Instance->CR2 |= TIM_CR2_TI1S; - - /* Select the TIM_TS_TI1F_ED signal as Input trigger for the TIM */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI1F_ED; - - /* Use the TIM_TS_TI1F_ED signal to reset the TIM counter each edge detection */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_RESET; - - /* Program channel 2 in PWM 2 mode with the desired Commutation_Delay*/ - OC_Config.OCFastMode = TIM_OCFAST_DISABLE; - OC_Config.OCIdleState = TIM_OCIDLESTATE_RESET; - OC_Config.OCMode = TIM_OCMODE_PWM2; - OC_Config.OCNIdleState = TIM_OCNIDLESTATE_RESET; - OC_Config.OCNPolarity = TIM_OCNPOLARITY_HIGH; - OC_Config.OCPolarity = TIM_OCPOLARITY_HIGH; - OC_Config.Pulse = sConfig->Commutation_Delay; - - TIM_OC2_SetConfig(htim->Instance, &OC_Config); - - /* Select OC2REF as trigger output on TRGO: write the MMS bits in the TIMx_CR2 - register to 101 */ - htim->Instance->CR2 &= ~TIM_CR2_MMS; - htim->Instance->CR2 |= TIM_TRGO_OC2REF; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM Hall Sensor interface - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->HallSensor_MspDeInitCallback == NULL) - { - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - } - /* DeInit the low level hardware */ - htim->HallSensor_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIMEx_HallSensor_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Hall Sensor MSP. - * @param htim TIM Hall Sensor Interface handle - * @retval None - */ -__weak void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_HallSensor_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Hall Sensor MSP. - * @param htim TIM Hall Sensor Interface handle - * @retval None - */ -__weak void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_HallSensor_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Hall Sensor Interface. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall sensor Interface. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1, 2 and 3 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Hall Sensor Interface in interrupt mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the capture compare Interrupts 1 event */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall Sensor Interface in interrupt mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts event */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Hall Sensor Interface in DMA mode. - * @param htim TIM Hall Sensor Interface handle - * @param pData The destination Buffer address. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel state */ - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Set the DMA Input Capture 1 Callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream for Capture 1*/ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the capture compare 1 Interrupt */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall Sensor Interface in DMA mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - - /* Disable the capture compare Interrupts 1 event */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions - * @brief Timer Complementary Output Compare functions - * -@verbatim - ============================================================================== - ##### Timer Complementary Output Compare functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary Output Compare/PWM. - (+) Stop the Complementary Output Compare/PWM. - (+) Start the Complementary Output Compare/PWM and enable interrupts. - (+) Stop the Complementary Output Compare/PWM and disable interrupts. - (+) Start the Complementary Output Compare/PWM and enable DMA transfers. - (+) Stop the Complementary Output Compare/PWM and disable DMA transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the TIM Output Compare signal generation on the complementary - * output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Output Compare signal generation on the complementary - * output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Output Compare signal generation in interrupt mode - * on the complementary output. - * @param htim TIM OC handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the TIM Break interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); - - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in interrupt mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpccer; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the TIM Break interrupt (only if no more channel is active) */ - tmpccer = htim->Instance->CCER; - if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) - { - __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); - } - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Output Compare signal generation in DMA mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in DMA mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions - * @brief Timer Complementary PWM functions - * -@verbatim - ============================================================================== - ##### Timer Complementary PWM functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary PWM. - (+) Stop the Complementary PWM. - (+) Start the Complementary PWM and enable interrupts. - (+) Stop the Complementary PWM and disable interrupts. - (+) Start the Complementary PWM and enable DMA transfers. - (+) Stop the Complementary PWM and disable DMA transfers. - (+) Start the Complementary Input Capture measurement. - (+) Stop the Complementary Input Capture. - (+) Start the Complementary Input Capture and enable interrupts. - (+) Stop the Complementary Input Capture and disable interrupts. - (+) Start the Complementary Input Capture and enable DMA transfers. - (+) Stop the Complementary Input Capture and disable DMA transfers. - (+) Start the Complementary One Pulse generation. - (+) Stop the Complementary One Pulse. - (+) Start the Complementary One Pulse and enable interrupts. - (+) Stop the Complementary One Pulse and disable interrupts. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the PWM signal generation on the complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the PWM signal generation on the complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the PWM signal generation in interrupt mode on the - * complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the TIM Break interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); - - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the PWM signal generation in interrupt mode on the - * complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpccer; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the TIM Break interrupt (only if no more channel is active) */ - tmpccer = htim->Instance->CCER; - if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) - { - __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); - } - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM PWM signal generation in DMA mode on the - * complementary output - * @param htim TIM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM PWM signal generation in DMA mode on the complementary - * output - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions - * @brief Timer Complementary One Pulse functions - * -@verbatim - ============================================================================== - ##### Timer Complementary One Pulse functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary One Pulse generation. - (+) Stop the Complementary One Pulse. - (+) Start the Complementary One Pulse and enable interrupts. - (+) Stop the Complementary One Pulse and disable interrupts. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the TIM One Pulse signal generation on the complementary - * output. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to enable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation on the complementary - * output. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to disable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Disable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM One Pulse signal generation in interrupt mode on the - * complementary channel. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to enable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - - /* Enable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation in interrupt mode on the - * complementary channel. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to disable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - - /* Disable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Configure the commutation event in case of use of the Hall sensor interface. - (+) Configure Output channels for OC and PWM mode. - - (+) Configure Complementary channels, break features and dead time. - (+) Configure Master synchronization. - (+) Configure timer remapping capabilities. - -@endverbatim - * @{ - */ - -/** - * @brief Configure the TIM commutation event sequence. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Disable Commutation Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); - - /* Disable Commutation DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configure the TIM commutation event sequence with interrupt. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Disable Commutation DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); - - /* Enable the Commutation Interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configure the TIM commutation event sequence with DMA. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @note The user should configure the DMA in his own software, in This function only the COMDE bit is set - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Enable the Commutation DMA Request */ - /* Set the DMA Commutation Callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError; - - /* Disable Commutation Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); - - /* Enable the Commutation DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIM in master mode. - * @param htim TIM handle. - * @param sMasterConfig pointer to a TIM_MasterConfigTypeDef structure that - * contains the selected trigger output (TRGO) and the Master/Slave - * mode. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, - TIM_MasterConfigTypeDef *sMasterConfig) -{ - uint32_t tmpcr2; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger)); - assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode)); - - /* Check input state */ - __HAL_LOCK(htim); - - /* Change the handler state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Get the TIMx CR2 register value */ - tmpcr2 = htim->Instance->CR2; - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Reset the MMS Bits */ - tmpcr2 &= ~TIM_CR2_MMS; - /* Select the TRGO source */ - tmpcr2 |= sMasterConfig->MasterOutputTrigger; - - /* Update TIMx CR2 */ - htim->Instance->CR2 = tmpcr2; - - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - /* Reset the MSM Bit */ - tmpsmcr &= ~TIM_SMCR_MSM; - /* Set master mode */ - tmpsmcr |= sMasterConfig->MasterSlaveMode; - - /* Update TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - } - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State - * and the AOE(automatic output enable). - * @param htim TIM handle - * @param sBreakDeadTimeConfig pointer to a TIM_ConfigBreakDeadConfigTypeDef structure that - * contains the BDTR Register configuration information for the TIM peripheral. - * @note Interrupts can be generated when an active level is detected on the - * break input, the break 2 input or the system break input. Break - * interrupt can be enabled by calling the @ref __HAL_TIM_ENABLE_IT macro. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, - TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig) -{ - /* Keep this variable initialized to 0 as it is used to configure BDTR register */ - uint32_t tmpbdtr = 0U; - - /* Check the parameters */ - assert_param(IS_TIM_BREAK_INSTANCE(htim->Instance)); - assert_param(IS_TIM_OSSR_STATE(sBreakDeadTimeConfig->OffStateRunMode)); - assert_param(IS_TIM_OSSI_STATE(sBreakDeadTimeConfig->OffStateIDLEMode)); - assert_param(IS_TIM_LOCK_LEVEL(sBreakDeadTimeConfig->LockLevel)); - assert_param(IS_TIM_DEADTIME(sBreakDeadTimeConfig->DeadTime)); - assert_param(IS_TIM_BREAK_STATE(sBreakDeadTimeConfig->BreakState)); - assert_param(IS_TIM_BREAK_POLARITY(sBreakDeadTimeConfig->BreakPolarity)); - assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(sBreakDeadTimeConfig->AutomaticOutput)); - - /* Check input state */ - __HAL_LOCK(htim); - - /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, - the OSSI State, the dead time value and the Automatic Output Enable Bit */ - - /* Set the BDTR bits */ - MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, sBreakDeadTimeConfig->DeadTime); - MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, sBreakDeadTimeConfig->LockLevel); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, sBreakDeadTimeConfig->OffStateIDLEMode); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, sBreakDeadTimeConfig->OffStateRunMode); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, sBreakDeadTimeConfig->BreakState); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, sBreakDeadTimeConfig->BreakPolarity); - MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, sBreakDeadTimeConfig->AutomaticOutput); - - - /* Set TIMx_BDTR */ - htim->Instance->BDTR = tmpbdtr; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIMx Remapping input capabilities. - * @param htim TIM handle. - * @param Remap specifies the TIM remapping source. - * For TIM1, the parameter can have the following values: (**) - * @arg TIM_TIM1_TIM3_TRGO: TIM1 ITR2 is connected to TIM3 TRGO - * @arg TIM_TIM1_LPTIM: TIM1 ITR2 is connected to LPTIM1 output - * - * For TIM2, the parameter can have the following values: (**) - * @arg TIM_TIM2_TIM8_TRGO: TIM2 ITR1 is connected to TIM8 TRGO (*) - * @arg TIM_TIM2_ETH_PTP: TIM2 ITR1 is connected to PTP trigger output (*) - * @arg TIM_TIM2_USBFS_SOF: TIM2 ITR1 is connected to OTG FS SOF - * @arg TIM_TIM2_USBHS_SOF: TIM2 ITR1 is connected to OTG FS SOF - * - * For TIM5, the parameter can have the following values: - * @arg TIM_TIM5_GPIO: TIM5 TI4 is connected to GPIO - * @arg TIM_TIM5_LSI: TIM5 TI4 is connected to LSI - * @arg TIM_TIM5_LSE: TIM5 TI4 is connected to LSE - * @arg TIM_TIM5_RTC: TIM5 TI4 is connected to the RTC wakeup interrupt - * @arg TIM_TIM5_TIM3_TRGO: TIM5 ITR1 is connected to TIM3 TRGO (*) - * @arg TIM_TIM5_LPTIM: TIM5 ITR1 is connected to LPTIM1 output (*) - * - * For TIM9, the parameter can have the following values: (**) - * @arg TIM_TIM9_TIM3_TRGO: TIM9 ITR1 is connected to TIM3 TRGO - * @arg TIM_TIM9_LPTIM: TIM9 ITR1 is connected to LPTIM1 output - * - * For TIM11, the parameter can have the following values: - * @arg TIM_TIM11_GPIO: TIM11 TI1 is connected to GPIO - * @arg TIM_TIM11_HSE: TIM11 TI1 is connected to HSE_RTC clock - * @arg TIM_TIM11_SPDIFRX: TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC (*) - * - * (*) Value not defined in all devices. \n - * (**) Register not available in all devices. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap) -{ - - /* Check parameters */ - assert_param(IS_TIM_REMAP(htim->Instance, Remap)); - - __HAL_LOCK(htim); - -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) - if ((Remap & LPTIM_REMAP_MASK) == LPTIM_REMAP_MASK) - { - /* Connect TIMx internal trigger to LPTIM1 output */ - __HAL_RCC_LPTIM1_CLK_ENABLE(); - MODIFY_REG(LPTIM1->OR, - (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), - Remap & ~(LPTIM_REMAP_MASK)); - } - else - { - /* Set the Timer remapping configuration */ - WRITE_REG(htim->Instance->OR, Remap); - } -#else - /* Set the Timer remapping configuration */ - WRITE_REG(htim->Instance->OR, Remap); -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions - * @brief Extended Callbacks functions - * -@verbatim - ============================================================================== - ##### Extended Callbacks functions ##### - ============================================================================== - [..] - This section provides Extended TIM callback functions: - (+) Timer Commutation callback - (+) Timer Break callback - -@endverbatim - * @{ - */ - -/** - * @brief Hall commutation changed callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_CommutCallback could be implemented in the user file - */ -} -/** - * @brief Hall commutation changed half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_CommutHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Break detection callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_BreakCallback could be implemented in the user file - */ -} -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions - * @brief Extended Peripheral State functions - * -@verbatim - ============================================================================== - ##### Extended Peripheral State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the TIM Hall Sensor interface handle state. - * @param htim TIM Hall Sensor handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return actual state of the TIM complementary channel. - * @param htim TIM handle - * @param ChannelN TIM Complementary channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @retval TIM Complementary channel state - */ -HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN) -{ - HAL_TIM_ChannelStateTypeDef channel_state; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, ChannelN)); - - channel_state = TIM_CHANNEL_N_STATE_GET(htim, ChannelN); - - return channel_state; -} -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup TIMEx_Private_Functions TIM Extended Private Functions - * @{ - */ - -/** - * @brief TIM DMA Commutation callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationCallback(htim); -#else - HAL_TIMEx_CommutCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Commutation half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationHalfCpltCallback(htim); -#else - HAL_TIMEx_CommutHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - - -/** - * @brief TIM DMA Delay Pulse complete callback (complementary channel). - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA error callback (complementary channel) - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->ErrorCallback(htim); -#else - HAL_TIM_ErrorCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel xN. - * @param TIMx to select the TIM peripheral - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @param ChannelNState specifies the TIM Channel CCxNE bit new state. - * This parameter can be: TIM_CCxN_ENABLE or TIM_CCxN_Disable. - * @retval None - */ -static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState) -{ - uint32_t tmp; - - tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ - - /* Reset the CCxNE Bit */ - TIMx->CCER &= ~tmp; - - /* Set or reset the CCxNE Bit */ - TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ -} -/** - * @} - */ - -#endif /* HAL_TIM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim_ex.c + * @author MCD Application Team + * @brief TIM HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Timer Extended peripheral: + * + Time Hall Sensor Interface Initialization + * + Time Hall Sensor Interface Start + * + Time Complementary signal break and dead time configuration + * + Time Master and Slave synchronization configuration + * + Timer remapping capabilities configuration + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### TIMER Extended features ##### + ============================================================================== + [..] + The Timer Extended features include: + (#) Complementary outputs with programmable dead-time for : + (++) Output Compare + (++) PWM generation (Edge and Center-aligned Mode) + (++) One-pulse mode output + (#) Synchronization circuit to control the timer with external signals and to + interconnect several timers together. + (#) Break input to put the timer output signals in reset state or in a known state. + (#) Supports incremental (quadrature) encoder and hall-sensor circuitry for + positioning purposes + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the TIM low level resources by implementing the following functions + depending on the selected feature: + (++) Hall Sensor output : HAL_TIMEx_HallSensor_MspInit() + + (#) Initialize the TIM low level resources : + (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); + (##) TIM pins configuration + (+++) Enable the clock for the TIM GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); + + (#) The external Clock can be configured, if needed (the default clock is the + internal clock from the APBx), using the following function: + HAL_TIM_ConfigClockSource, the clock configuration should be done before + any start function. + + (#) Configure the TIM in the desired functioning mode using one of the + initialization function of this driver: + (++) HAL_TIMEx_HallSensor_Init() and HAL_TIMEx_ConfigCommutEvent(): to use the + Timer Hall Sensor Interface and the commutation event with the corresponding + Interrupt and DMA request if needed (Note that One Timer is used to interface + with the Hall sensor Interface and another Timer should be used to use + the commutation event). + + (#) Activate the TIM peripheral using one of the start functions: + (++) Complementary Output Compare : HAL_TIMEx_OCN_Start(), HAL_TIMEx_OCN_Start_DMA(), + HAL_TIMEx_OCN_Start_IT() + (++) Complementary PWM generation : HAL_TIMEx_PWMN_Start(), HAL_TIMEx_PWMN_Start_DMA(), + HAL_TIMEx_PWMN_Start_IT() + (++) Complementary One-pulse mode output : HAL_TIMEx_OnePulseN_Start(), HAL_TIMEx_OnePulseN_Start_IT() + (++) Hall Sensor output : HAL_TIMEx_HallSensor_Start(), HAL_TIMEx_HallSensor_Start_DMA(), + HAL_TIMEx_HallSensor_Start_IT(). + + @endverbatim + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup TIMEx TIMEx + * @brief TIM Extended HAL module driver + * @{ + */ + +#ifdef HAL_TIM_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma); +static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState); + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup TIMEx_Exported_Functions TIM Extended Exported Functions + * @{ + */ + +/** @defgroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions + * @brief Timer Hall Sensor functions + * +@verbatim + ============================================================================== + ##### Timer Hall Sensor functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure TIM HAL Sensor. + (+) De-initialize TIM HAL Sensor. + (+) Start the Hall Sensor Interface. + (+) Stop the Hall Sensor Interface. + (+) Start the Hall Sensor Interface and enable interrupts. + (+) Stop the Hall Sensor Interface and disable interrupts. + (+) Start the Hall Sensor Interface and enable DMA transfers. + (+) Stop the Hall Sensor Interface and disable DMA transfers. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Hall Sensor Interface and initialize the associated handle. + * @note When the timer instance is initialized in Hall Sensor Interface mode, + * timer channels 1 and channel 2 are reserved and cannot be used for + * other purpose. + * @param htim TIM Hall Sensor Interface handle + * @param sConfig TIM Hall Sensor configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig) +{ + TIM_OC_InitTypeDef OC_Config; + + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + assert_param(IS_TIM_IC_POLARITY(sConfig->IC1Polarity)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy week callbacks */ + TIM_ResetCallback(htim); + + if (htim->HallSensor_MspInitCallback == NULL) + { + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->HallSensor_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIMEx_HallSensor_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Configure the Time base in the Encoder Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Configure the Channel 1 as Input Channel to interface with the three Outputs of the Hall sensor */ + TIM_TI1_SetConfig(htim->Instance, sConfig->IC1Polarity, TIM_ICSELECTION_TRC, sConfig->IC1Filter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + /* Set the IC1PSC value */ + htim->Instance->CCMR1 |= sConfig->IC1Prescaler; + + /* Enable the Hall sensor interface (XOR function of the three inputs) */ + htim->Instance->CR2 |= TIM_CR2_TI1S; + + /* Select the TIM_TS_TI1F_ED signal as Input trigger for the TIM */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI1F_ED; + + /* Use the TIM_TS_TI1F_ED signal to reset the TIM counter each edge detection */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_RESET; + + /* Program channel 2 in PWM 2 mode with the desired Commutation_Delay*/ + OC_Config.OCFastMode = TIM_OCFAST_DISABLE; + OC_Config.OCIdleState = TIM_OCIDLESTATE_RESET; + OC_Config.OCMode = TIM_OCMODE_PWM2; + OC_Config.OCNIdleState = TIM_OCNIDLESTATE_RESET; + OC_Config.OCNPolarity = TIM_OCNPOLARITY_HIGH; + OC_Config.OCPolarity = TIM_OCPOLARITY_HIGH; + OC_Config.Pulse = sConfig->Commutation_Delay; + + TIM_OC2_SetConfig(htim->Instance, &OC_Config); + + /* Select OC2REF as trigger output on TRGO: write the MMS bits in the TIMx_CR2 + register to 101 */ + htim->Instance->CR2 &= ~TIM_CR2_MMS; + htim->Instance->CR2 |= TIM_TRGO_OC2REF; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM Hall Sensor interface + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->HallSensor_MspDeInitCallback == NULL) + { + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + } + /* DeInit the low level hardware */ + htim->HallSensor_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIMEx_HallSensor_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Hall Sensor MSP. + * @param htim TIM Hall Sensor Interface handle + * @retval None + */ +__weak void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_HallSensor_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Hall Sensor MSP. + * @param htim TIM Hall Sensor Interface handle + * @retval None + */ +__weak void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_HallSensor_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Hall Sensor Interface. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall sensor Interface. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1, 2 and 3 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Hall Sensor Interface in interrupt mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the capture compare Interrupts 1 event */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall Sensor Interface in interrupt mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts event */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Hall Sensor Interface in DMA mode. + * @param htim TIM Hall Sensor Interface handle + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel state */ + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Set the DMA Input Capture 1 Callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream for Capture 1*/ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the capture compare 1 Interrupt */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall Sensor Interface in DMA mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + + /* Disable the capture compare Interrupts 1 event */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions + * @brief Timer Complementary Output Compare functions + * +@verbatim + ============================================================================== + ##### Timer Complementary Output Compare functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary Output Compare/PWM. + (+) Stop the Complementary Output Compare/PWM. + (+) Start the Complementary Output Compare/PWM and enable interrupts. + (+) Stop the Complementary Output Compare/PWM and disable interrupts. + (+) Start the Complementary Output Compare/PWM and enable DMA transfers. + (+) Stop the Complementary Output Compare/PWM and disable DMA transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the TIM Output Compare signal generation on the complementary + * output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Output Compare signal generation on the complementary + * output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Output Compare signal generation in interrupt mode + * on the complementary output. + * @param htim TIM OC handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the TIM Break interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); + + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in interrupt mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpccer; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the TIM Break interrupt (only if no more channel is active) */ + tmpccer = htim->Instance->CCER; + if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) + { + __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); + } + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Output Compare signal generation in DMA mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in DMA mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions + * @brief Timer Complementary PWM functions + * +@verbatim + ============================================================================== + ##### Timer Complementary PWM functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary PWM. + (+) Stop the Complementary PWM. + (+) Start the Complementary PWM and enable interrupts. + (+) Stop the Complementary PWM and disable interrupts. + (+) Start the Complementary PWM and enable DMA transfers. + (+) Stop the Complementary PWM and disable DMA transfers. + (+) Start the Complementary Input Capture measurement. + (+) Stop the Complementary Input Capture. + (+) Start the Complementary Input Capture and enable interrupts. + (+) Stop the Complementary Input Capture and disable interrupts. + (+) Start the Complementary Input Capture and enable DMA transfers. + (+) Stop the Complementary Input Capture and disable DMA transfers. + (+) Start the Complementary One Pulse generation. + (+) Stop the Complementary One Pulse. + (+) Start the Complementary One Pulse and enable interrupts. + (+) Stop the Complementary One Pulse and disable interrupts. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the PWM signal generation on the complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the PWM signal generation on the complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the PWM signal generation in interrupt mode on the + * complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the TIM Break interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); + + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the PWM signal generation in interrupt mode on the + * complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpccer; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the TIM Break interrupt (only if no more channel is active) */ + tmpccer = htim->Instance->CCER; + if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) + { + __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); + } + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM PWM signal generation in DMA mode on the + * complementary output + * @param htim TIM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM PWM signal generation in DMA mode on the complementary + * output + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions + * @brief Timer Complementary One Pulse functions + * +@verbatim + ============================================================================== + ##### Timer Complementary One Pulse functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary One Pulse generation. + (+) Stop the Complementary One Pulse. + (+) Start the Complementary One Pulse and enable interrupts. + (+) Stop the Complementary One Pulse and disable interrupts. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the TIM One Pulse signal generation on the complementary + * output. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to enable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation on the complementary + * output. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to disable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Disable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM One Pulse signal generation in interrupt mode on the + * complementary channel. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to enable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + + /* Enable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation in interrupt mode on the + * complementary channel. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to disable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + + /* Disable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Configure the commutation event in case of use of the Hall sensor interface. + (+) Configure Output channels for OC and PWM mode. + + (+) Configure Complementary channels, break features and dead time. + (+) Configure Master synchronization. + (+) Configure timer remapping capabilities. + +@endverbatim + * @{ + */ + +/** + * @brief Configure the TIM commutation event sequence. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Disable Commutation Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); + + /* Disable Commutation DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configure the TIM commutation event sequence with interrupt. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Disable Commutation DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); + + /* Enable the Commutation Interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configure the TIM commutation event sequence with DMA. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @note The user should configure the DMA in his own software, in This function only the COMDE bit is set + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Enable the Commutation DMA Request */ + /* Set the DMA Commutation Callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError; + + /* Disable Commutation Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); + + /* Enable the Commutation DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIM in master mode. + * @param htim TIM handle. + * @param sMasterConfig pointer to a TIM_MasterConfigTypeDef structure that + * contains the selected trigger output (TRGO) and the Master/Slave + * mode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, + TIM_MasterConfigTypeDef *sMasterConfig) +{ + uint32_t tmpcr2; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger)); + assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode)); + + /* Check input state */ + __HAL_LOCK(htim); + + /* Change the handler state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Get the TIMx CR2 register value */ + tmpcr2 = htim->Instance->CR2; + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Reset the MMS Bits */ + tmpcr2 &= ~TIM_CR2_MMS; + /* Select the TRGO source */ + tmpcr2 |= sMasterConfig->MasterOutputTrigger; + + /* Update TIMx CR2 */ + htim->Instance->CR2 = tmpcr2; + + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + /* Reset the MSM Bit */ + tmpsmcr &= ~TIM_SMCR_MSM; + /* Set master mode */ + tmpsmcr |= sMasterConfig->MasterSlaveMode; + + /* Update TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + } + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State + * and the AOE(automatic output enable). + * @param htim TIM handle + * @param sBreakDeadTimeConfig pointer to a TIM_ConfigBreakDeadConfigTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @note Interrupts can be generated when an active level is detected on the + * break input, the break 2 input or the system break input. Break + * interrupt can be enabled by calling the @ref __HAL_TIM_ENABLE_IT macro. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, + TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig) +{ + /* Keep this variable initialized to 0 as it is used to configure BDTR register */ + uint32_t tmpbdtr = 0U; + + /* Check the parameters */ + assert_param(IS_TIM_BREAK_INSTANCE(htim->Instance)); + assert_param(IS_TIM_OSSR_STATE(sBreakDeadTimeConfig->OffStateRunMode)); + assert_param(IS_TIM_OSSI_STATE(sBreakDeadTimeConfig->OffStateIDLEMode)); + assert_param(IS_TIM_LOCK_LEVEL(sBreakDeadTimeConfig->LockLevel)); + assert_param(IS_TIM_DEADTIME(sBreakDeadTimeConfig->DeadTime)); + assert_param(IS_TIM_BREAK_STATE(sBreakDeadTimeConfig->BreakState)); + assert_param(IS_TIM_BREAK_POLARITY(sBreakDeadTimeConfig->BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(sBreakDeadTimeConfig->AutomaticOutput)); + + /* Check input state */ + __HAL_LOCK(htim); + + /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + + /* Set the BDTR bits */ + MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, sBreakDeadTimeConfig->DeadTime); + MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, sBreakDeadTimeConfig->LockLevel); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, sBreakDeadTimeConfig->OffStateIDLEMode); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, sBreakDeadTimeConfig->OffStateRunMode); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, sBreakDeadTimeConfig->BreakState); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, sBreakDeadTimeConfig->BreakPolarity); + MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, sBreakDeadTimeConfig->AutomaticOutput); + + + /* Set TIMx_BDTR */ + htim->Instance->BDTR = tmpbdtr; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIMx Remapping input capabilities. + * @param htim TIM handle. + * @param Remap specifies the TIM remapping source. + * For TIM1, the parameter can have the following values: (**) + * @arg TIM_TIM1_TIM3_TRGO: TIM1 ITR2 is connected to TIM3 TRGO + * @arg TIM_TIM1_LPTIM: TIM1 ITR2 is connected to LPTIM1 output + * + * For TIM2, the parameter can have the following values: (**) + * @arg TIM_TIM2_TIM8_TRGO: TIM2 ITR1 is connected to TIM8 TRGO (*) + * @arg TIM_TIM2_ETH_PTP: TIM2 ITR1 is connected to PTP trigger output (*) + * @arg TIM_TIM2_USBFS_SOF: TIM2 ITR1 is connected to OTG FS SOF + * @arg TIM_TIM2_USBHS_SOF: TIM2 ITR1 is connected to OTG FS SOF + * + * For TIM5, the parameter can have the following values: + * @arg TIM_TIM5_GPIO: TIM5 TI4 is connected to GPIO + * @arg TIM_TIM5_LSI: TIM5 TI4 is connected to LSI + * @arg TIM_TIM5_LSE: TIM5 TI4 is connected to LSE + * @arg TIM_TIM5_RTC: TIM5 TI4 is connected to the RTC wakeup interrupt + * @arg TIM_TIM5_TIM3_TRGO: TIM5 ITR1 is connected to TIM3 TRGO (*) + * @arg TIM_TIM5_LPTIM: TIM5 ITR1 is connected to LPTIM1 output (*) + * + * For TIM9, the parameter can have the following values: (**) + * @arg TIM_TIM9_TIM3_TRGO: TIM9 ITR1 is connected to TIM3 TRGO + * @arg TIM_TIM9_LPTIM: TIM9 ITR1 is connected to LPTIM1 output + * + * For TIM11, the parameter can have the following values: + * @arg TIM_TIM11_GPIO: TIM11 TI1 is connected to GPIO + * @arg TIM_TIM11_HSE: TIM11 TI1 is connected to HSE_RTC clock + * @arg TIM_TIM11_SPDIFRX: TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC (*) + * + * (*) Value not defined in all devices. \n + * (**) Register not available in all devices. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap) +{ + + /* Check parameters */ + assert_param(IS_TIM_REMAP(htim->Instance, Remap)); + + __HAL_LOCK(htim); + +#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) + if ((Remap & LPTIM_REMAP_MASK) == LPTIM_REMAP_MASK) + { + /* Connect TIMx internal trigger to LPTIM1 output */ + __HAL_RCC_LPTIM1_CLK_ENABLE(); + MODIFY_REG(LPTIM1->OR, + (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), + Remap & ~(LPTIM_REMAP_MASK)); + } + else + { + /* Set the Timer remapping configuration */ + WRITE_REG(htim->Instance->OR, Remap); + } +#else + /* Set the Timer remapping configuration */ + WRITE_REG(htim->Instance->OR, Remap); +#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions + * @brief Extended Callbacks functions + * +@verbatim + ============================================================================== + ##### Extended Callbacks functions ##### + ============================================================================== + [..] + This section provides Extended TIM callback functions: + (+) Timer Commutation callback + (+) Timer Break callback + +@endverbatim + * @{ + */ + +/** + * @brief Hall commutation changed callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_CommutCallback could be implemented in the user file + */ +} +/** + * @brief Hall commutation changed half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_CommutHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Break detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_BreakCallback could be implemented in the user file + */ +} +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions + * @brief Extended Peripheral State functions + * +@verbatim + ============================================================================== + ##### Extended Peripheral State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the TIM Hall Sensor interface handle state. + * @param htim TIM Hall Sensor handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return actual state of the TIM complementary channel. + * @param htim TIM handle + * @param ChannelN TIM Complementary channel + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 + * @arg TIM_CHANNEL_2: TIM Channel 2 + * @arg TIM_CHANNEL_3: TIM Channel 3 + * @retval TIM Complementary channel state + */ +HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN) +{ + HAL_TIM_ChannelStateTypeDef channel_state; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, ChannelN)); + + channel_state = TIM_CHANNEL_N_STATE_GET(htim, ChannelN); + + return channel_state; +} +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup TIMEx_Private_Functions TIM Extended Private Functions + * @{ + */ + +/** + * @brief TIM DMA Commutation callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationCallback(htim); +#else + HAL_TIMEx_CommutCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Commutation half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationHalfCpltCallback(htim); +#else + HAL_TIMEx_CommutHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + + +/** + * @brief TIM DMA Delay Pulse complete callback (complementary channel). + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA error callback (complementary channel) + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->ErrorCallback(htim); +#else + HAL_TIM_ErrorCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx to select the TIM peripheral + * @param Channel specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 + * @arg TIM_CHANNEL_2: TIM Channel 2 + * @arg TIM_CHANNEL_3: TIM Channel 3 + * @param ChannelNState specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_ENABLE or TIM_CCxN_Disable. + * @retval None + */ +static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState) +{ + uint32_t tmp; + + tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ + + /* Reset the CCxNE Bit */ + TIMx->CCER &= ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ +} +/** + * @} + */ + +#endif /* HAL_TIM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c index 36b7317..d958ad6 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c @@ -1,3751 +1,3751 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_uart.c - * @author MCD Application Team - * @brief UART HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Universal Asynchronous Receiver Transmitter Peripheral (UART). - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The UART HAL driver can be used as follows: - - (#) Declare a UART_HandleTypeDef handle structure (eg. UART_HandleTypeDef huart). - (#) Initialize the UART low level resources by implementing the HAL_UART_MspInit() API: - (##) Enable the USARTx interface clock. - (##) UART pins configuration: - (+++) Enable the clock for the UART GPIOs. - (+++) Configure the UART TX/RX pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_UART_Transmit_IT() - and HAL_UART_Receive_IT() APIs): - (+++) Configure the USARTx interrupt priority. - (+++) Enable the NVIC USART IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_UART_Transmit_DMA() - and HAL_UART_Receive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required - Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx stream. - (+++) Associate the initialized DMA handle to the UART DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the DMA Tx/Rx stream. - (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle - (used for last byte sending completion detection in DMA non circular mode) - - (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware - flow control and Mode(Receiver/Transmitter) in the huart Init structure. - - (#) For the UART asynchronous mode, initialize the UART registers by calling - the HAL_UART_Init() API. - - (#) For the UART Half duplex mode, initialize the UART registers by calling - the HAL_HalfDuplex_Init() API. - - (#) For the LIN mode, initialize the UART registers by calling the HAL_LIN_Init() API. - - (#) For the Multi-Processor mode, initialize the UART registers by calling - the HAL_MultiProcessor_Init() API. - - [..] - (@) The specific UART interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_UART_ENABLE_IT() and __HAL_UART_DISABLE_IT() inside the transmit - and receive process. - - [..] - (@) These APIs (HAL_UART_Init() and HAL_HalfDuplex_Init()) configure also the - low level Hardware GPIO, CLOCK, CORTEX...etc) by calling the customized - HAL_UART_MspInit() API. - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_UART_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_UART_RegisterCallback() to register a user callback. - Function HAL_UART_RegisterCallback() allows to register following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : UART MspInit. - (+) MspDeInitCallback : UART MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_UART_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : UART MspInit. - (+) MspDeInitCallback : UART MspDeInit. - - [..] - For specific callback RxEventCallback, use dedicated registration/reset functions: - respectively HAL_UART_RegisterRxEventCallback() , HAL_UART_UnRegisterRxEventCallback(). - - [..] - By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_UART_Init() - and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_UART_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_UART_STATE_READY or HAL_UART_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_UART_RegisterCallback() before calling HAL_UART_DeInit() - or HAL_UART_Init() function. - - [..] - When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - [..] - Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_UART_Transmit() - (+) Receive an amount of data in blocking mode using HAL_UART_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_UART_Transmit_IT() - (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_UART_Receive_IT() - (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxCpltCallback - (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_UART_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_UART_Transmit_DMA() - (+) At transmission end of half transfer HAL_UART_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxHalfCpltCallback - (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_UART_Receive_DMA() - (+) At reception end of half transfer HAL_UART_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxHalfCpltCallback - (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxCpltCallback - (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_UART_ErrorCallback - (+) Pause the DMA Transfer using HAL_UART_DMAPause() - (+) Resume the DMA Transfer using HAL_UART_DMAResume() - (+) Stop the DMA Transfer using HAL_UART_DMAStop() - - - [..] This subsection also provides a set of additional functions providing enhanced reception - services to user. (For example, these functions allow application to handle use cases - where number of data to be received is unknown). - - (#) Compared to standard reception services which only consider number of received - data elements as reception completion criteria, these functions also consider additional events - as triggers for updating reception status to caller : - (+) Detection of inactivity period (RX line has not been active for a given period). - (++) RX inactivity detected by IDLE event, i.e. RX line has been in idle state (normally high state) - for 1 frame time, after last received byte. - - (#) There are two mode of transfer: - (+) Blocking mode: The reception is performed in polling mode, until either expected number of data is received, - or till IDLE event occurs. Reception is handled only during function execution. - When function exits, no data reception could occur. HAL status and number of actually received data elements, - are returned by function after finishing transfer. - (+) Non-Blocking mode: The reception is performed using Interrupts or DMA. - These API's return the HAL status. - The end of the data processing will be indicated through the - dedicated UART IRQ when using Interrupt mode or the DMA IRQ when using DMA mode. - The HAL_UARTEx_RxEventCallback() user callback will be executed during Receive process - The HAL_UART_ErrorCallback()user callback will be executed when a reception error is detected. - - (#) Blocking mode API: - (+) HAL_UARTEx_ReceiveToIdle() - - (#) Non-Blocking mode API with Interrupt: - (+) HAL_UARTEx_ReceiveToIdle_IT() - - (#) Non-Blocking mode API with DMA: - (+) HAL_UARTEx_ReceiveToIdle_DMA() - - - *** UART HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in UART HAL driver. - - (+) __HAL_UART_ENABLE: Enable the UART peripheral - (+) __HAL_UART_DISABLE: Disable the UART peripheral - (+) __HAL_UART_GET_FLAG : Check whether the specified UART flag is set or not - (+) __HAL_UART_CLEAR_FLAG : Clear the specified UART pending flag - (+) __HAL_UART_ENABLE_IT: Enable the specified UART interrupt - (+) __HAL_UART_DISABLE_IT: Disable the specified UART interrupt - (+) __HAL_UART_GET_IT_SOURCE: Check whether the specified UART interrupt has occurred or not - - [..] - (@) You can refer to the UART HAL driver header file for more useful macros - - @endverbatim - [..] - (@) Additional remark: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - the possible UART frame formats are as listed in the following table: - +-------------------------------------------------------------+ - | M bit | PCE bit | UART frame | - |---------------------|---------------------------------------| - | 0 | 0 | | SB | 8 bit data | STB | | - |---------|-----------|---------------------------------------| - | 0 | 1 | | SB | 7 bit data | PB | STB | | - |---------|-----------|---------------------------------------| - | 1 | 0 | | SB | 9 bit data | STB | | - |---------|-----------|---------------------------------------| - | 1 | 1 | | SB | 8 bit data | PB | STB | | - +-------------------------------------------------------------+ - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup UART UART - * @brief HAL UART module driver - * @{ - */ -#ifdef HAL_UART_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup UART_Private_Constants - * @{ - */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup UART_Private_Functions UART Private Functions - * @{ - */ - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -static void UART_EndTxTransfer(UART_HandleTypeDef *huart); -static void UART_EndRxTransfer(UART_HandleTypeDef *huart); -static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); -static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void UART_DMAError(DMA_HandleTypeDef *hdma); -static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout); -static void UART_SetConfig(UART_HandleTypeDef *huart); - -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ -/** @defgroup UART_Exported_Functions UART Exported Functions - * @{ - */ - -/** @defgroup UART_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the USARTx or the UARTy - in asynchronous mode. - (+) For the asynchronous mode only these parameters can be configured: - (++) Baud Rate - (++) Word Length - (++) Stop Bit - (++) Parity: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - please refer to Reference manual for possible UART frame formats. - (++) Hardware flow control - (++) Receiver/transmitter modes - (++) Over Sampling Method - [..] - The HAL_UART_Init(), HAL_HalfDuplex_Init(), HAL_LIN_Init() and HAL_MultiProcessor_Init() APIs - follow respectively the UART asynchronous, UART Half duplex, LIN and Multi-Processor configuration - procedures (details for the procedures are available in reference manual - (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs - RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs - RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs - RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the UART mode according to the specified parameters in - * the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - if (huart->Init.HwFlowCtl != UART_HWCONTROL_NONE) - { - /* The hardware flow control is available only for USART1, USART2, USART3 and USART6. - Except for STM32F446xx devices, that is available for USART1, USART2, USART3, USART6, UART4 and UART5. - */ - assert_param(IS_UART_HWFLOW_INSTANCE(huart->Instance)); - assert_param(IS_UART_HARDWARE_FLOW_CONTROL(huart->Init.HwFlowCtl)); - } - else - { - assert_param(IS_UART_INSTANCE(huart->Instance)); - } - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In asynchronous mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the half-duplex mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_HALFDUPLEX_INSTANCE(huart->Instance)); - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In half-duplex mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_IREN | USART_CR3_SCEN)); - - /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ - SET_BIT(huart->Instance->CR3, USART_CR3_HDSEL); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state*/ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the LIN mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param BreakDetectLength Specifies the LIN break detection length. - * This parameter can be one of the following values: - * @arg UART_LINBREAKDETECTLENGTH_10B: 10-bit break detection - * @arg UART_LINBREAKDETECTLENGTH_11B: 11-bit break detection - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the LIN UART instance */ - assert_param(IS_UART_LIN_INSTANCE(huart->Instance)); - - /* Check the Break detection length parameter */ - assert_param(IS_UART_LIN_BREAK_DETECT_LENGTH(BreakDetectLength)); - assert_param(IS_UART_LIN_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_LIN_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In LIN mode, the following bits must be kept cleared: - - CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_HDSEL | USART_CR3_IREN | USART_CR3_SCEN)); - - /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ - SET_BIT(huart->Instance->CR2, USART_CR2_LINEN); - - /* Set the USART LIN Break detection length. */ - CLEAR_BIT(huart->Instance->CR2, USART_CR2_LBDL); - SET_BIT(huart->Instance->CR2, BreakDetectLength); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state*/ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the Multi-Processor mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param Address USART address - * @param WakeUpMethod specifies the USART wake-up method. - * This parameter can be one of the following values: - * @arg UART_WAKEUPMETHOD_IDLELINE: Wake-up by an idle line detection - * @arg UART_WAKEUPMETHOD_ADDRESSMARK: Wake-up by an address mark - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Check the Address & wake up method parameters */ - assert_param(IS_UART_WAKEUPMETHOD(WakeUpMethod)); - assert_param(IS_UART_ADDRESS(Address)); - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In Multi-Processor mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register */ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - - /* Set the USART address node */ - CLEAR_BIT(huart->Instance->CR2, USART_CR2_ADD); - SET_BIT(huart->Instance->CR2, Address); - - /* Set the wake up method by setting the WAKE bit in the CR1 register */ - CLEAR_BIT(huart->Instance->CR1, USART_CR1_WAKE); - SET_BIT(huart->Instance->CR1, WakeUpMethod); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the UART peripheral. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_UART_DISABLE(huart); - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - if (huart->MspDeInitCallback == NULL) - { - huart->MspDeInitCallback = HAL_UART_MspDeInit; - } - /* DeInit the low level hardware */ - huart->MspDeInitCallback(huart); -#else - /* DeInit the low level hardware */ - HAL_UART_MspDeInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_RESET; - huart->RxState = HAL_UART_STATE_RESET; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Process Unlock */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief UART MSP Init. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_MspInit(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_MspInit could be implemented in the user file - */ -} - -/** - * @brief UART MSP DeInit. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_MspDeInit(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User UART Callback - * To be used instead of the weak predefined callback - * @param huart uart handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, - pUART_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - switch (CallbackID) - { - case HAL_UART_TX_HALFCOMPLETE_CB_ID : - huart->TxHalfCpltCallback = pCallback; - break; - - case HAL_UART_TX_COMPLETE_CB_ID : - huart->TxCpltCallback = pCallback; - break; - - case HAL_UART_RX_HALFCOMPLETE_CB_ID : - huart->RxHalfCpltCallback = pCallback; - break; - - case HAL_UART_RX_COMPLETE_CB_ID : - huart->RxCpltCallback = pCallback; - break; - - case HAL_UART_ERROR_CB_ID : - huart->ErrorCallback = pCallback; - break; - - case HAL_UART_ABORT_COMPLETE_CB_ID : - huart->AbortCpltCallback = pCallback; - break; - - case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : - huart->AbortTransmitCpltCallback = pCallback; - break; - - case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : - huart->AbortReceiveCpltCallback = pCallback; - break; - - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = pCallback; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (huart->gState == HAL_UART_STATE_RESET) - { - switch (CallbackID) - { - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = pCallback; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief Unregister an UART Callback - * UART callaback is redirected to the weak predefined callback - * @param huart uart handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(huart); - - if (HAL_UART_STATE_READY == huart->gState) - { - switch (CallbackID) - { - case HAL_UART_TX_HALFCOMPLETE_CB_ID : - huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_UART_TX_COMPLETE_CB_ID : - huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_UART_RX_HALFCOMPLETE_CB_ID : - huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_UART_RX_COMPLETE_CB_ID : - huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_UART_ERROR_CB_ID : - huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_UART_ABORT_COMPLETE_CB_ID : - huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : - huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - break; - - case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : - huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - break; - - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = HAL_UART_MspInit; /* Legacy weak MspInitCallback */ - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = HAL_UART_MspDeInit; /* Legacy weak MspDeInitCallback */ - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_UART_STATE_RESET == huart->gState) - { - switch (CallbackID) - { - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = HAL_UART_MspInit; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = HAL_UART_MspDeInit; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief Register a User UART Rx Event Callback - * To be used instead of the weak predefined callback - * @param huart Uart handle - * @param pCallback Pointer to the Rx Event Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - huart->RxEventCallback = pCallback; - } - else - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief UnRegister the UART Rx Event Callback - * UART Rx Event Callback is redirected to the weak HAL_UARTEx_RxEventCallback() predefined callback - * @param huart Uart handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */ - } - else - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - return status; -} -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group2 IO operation functions - * @brief UART Transmit and Receive functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - This subsection provides a set of functions allowing to manage the UART asynchronous - and Half duplex data transfers. - - (#) There are two modes of transfer: - (+) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (+) Non-Blocking mode: The communication is performed using Interrupts - or DMA, these API's return the HAL status. - The end of the data processing will be indicated through the - dedicated UART IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_UART_TxCpltCallback(), HAL_UART_RxCpltCallback() user callbacks - will be executed respectively at the end of the transmit or receive process - The HAL_UART_ErrorCallback()user callback will be executed when a communication error is detected. - - (#) Blocking mode API's are : - (+) HAL_UART_Transmit() - (+) HAL_UART_Receive() - - (#) Non-Blocking mode API's with Interrupt are : - (+) HAL_UART_Transmit_IT() - (+) HAL_UART_Receive_IT() - (+) HAL_UART_IRQHandler() - - (#) Non-Blocking mode API's with DMA are : - (+) HAL_UART_Transmit_DMA() - (+) HAL_UART_Receive_DMA() - (+) HAL_UART_DMAPause() - (+) HAL_UART_DMAResume() - (+) HAL_UART_DMAStop() - - (#) A set of Transfer Complete Callbacks are provided in Non_Blocking mode: - (+) HAL_UART_TxHalfCpltCallback() - (+) HAL_UART_TxCpltCallback() - (+) HAL_UART_RxHalfCpltCallback() - (+) HAL_UART_RxCpltCallback() - (+) HAL_UART_ErrorCallback() - - (#) Non-Blocking mode transfers could be aborted using Abort API's : - (+) HAL_UART_Abort() - (+) HAL_UART_AbortTransmit() - (+) HAL_UART_AbortReceive() - (+) HAL_UART_Abort_IT() - (+) HAL_UART_AbortTransmit_IT() - (+) HAL_UART_AbortReceive_IT() - - (#) For Abort services based on interrupts (HAL_UART_Abortxxx_IT), a set of Abort Complete Callbacks are provided: - (+) HAL_UART_AbortCpltCallback() - (+) HAL_UART_AbortTransmitCpltCallback() - (+) HAL_UART_AbortReceiveCpltCallback() - - (#) A Rx Event Reception Callback (Rx event notification) is available for Non_Blocking modes of enhanced reception services: - (+) HAL_UARTEx_RxEventCallback() - - (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. - Errors are handled as follows : - (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is - to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . - Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, - and HAL_UART_ErrorCallback() user callback is executed. Transfer is kept ongoing on UART side. - If user wants to abort it, Abort services should be called by user. - (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. - This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. - Error code is set to allow user to identify error type, and HAL_UART_ErrorCallback() user callback is executed. - - -@- In the Half duplex communication, it is forbidden to run the transmit - and receive process in parallel, the UART state HAL_UART_STATE_BUSY_TX_RX can't be useful. - -@endverbatim - * @{ - */ - -/** - * @brief Sends an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - const uint8_t *pdata8bits; - const uint16_t *pdata16bits; - uint32_t tickstart = 0U; - - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (const uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - while (huart->TxXferCount > 0U) - { - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (pdata8bits == NULL) - { - huart->Instance->DR = (uint16_t)(*pdata16bits & 0x01FFU); - pdata16bits++; - } - else - { - huart->Instance->DR = (uint8_t)(*pdata8bits & 0xFFU); - pdata8bits++; - } - huart->TxXferCount--; - } - - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* At end of Tx process, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - uint32_t tickstart = 0U; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Check the remain data to be received */ - while (huart->RxXferCount > 0U) - { - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (pdata8bits == NULL) - { - *pdata16bits = (uint16_t)(huart->Instance->DR & 0x01FF); - pdata16bits++; - } - else - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - pdata8bits++; - } - huart->RxXferCount--; - } - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sends an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size) -{ - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->pTxBuffPtr = pData; - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the UART Transmit data register empty Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_TXE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - /* Set Reception type to Standard reception */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return (UART_Start_Receive_IT(huart, pData, Size)); - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sends an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size) -{ - const uint32_t *tmp; - - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->pTxBuffPtr = pData; - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Set the UART DMA transfer complete callback */ - huart->hdmatx->XferCpltCallback = UART_DMATransmitCplt; - - /* Set the UART DMA Half transfer complete callback */ - huart->hdmatx->XferHalfCpltCallback = UART_DMATxHalfCplt; - - /* Set the DMA error callback */ - huart->hdmatx->XferErrorCallback = UART_DMAError; - - /* Set the DMA abort callback */ - huart->hdmatx->XferAbortCallback = NULL; - - /* Enable the UART transmit DMA stream */ - tmp = (const uint32_t *)&pData; - HAL_DMA_Start_IT(huart->hdmatx, *(const uint32_t *)tmp, (uint32_t)&huart->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_UART_CLEAR_FLAG(huart, UART_FLAG_TC); - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the UART CR3 register */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @note When the UART parity is enabled (PCE = 1) the received data contains the parity bit. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - /* Set Reception type to Standard reception */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return (UART_Start_Receive_DMA(huart, pData, Size)); - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Pauses the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart) -{ - uint32_t dmarequest = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - /* Disable the UART DMA Tx request */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - } - - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the UART DMA Rx request */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Resumes the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart) -{ - /* Process Locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_BUSY_TX) - { - /* Enable the UART DMA Tx request */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); - } - - if (huart->RxState == HAL_UART_STATE_BUSY_RX) - { - /* Clear the Overrun flag before resuming the Rx transfer*/ - __HAL_UART_CLEAR_OREFLAG(huart); - - /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ - if (huart->Init.Parity != UART_PARITY_NONE) - { - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); - } - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Enable the UART DMA Rx request */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Stops the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart) -{ - uint32_t dmarequest = 0x00U; - /* The Lock is not implemented on this API to allow the user application - to call the HAL UART API under callbacks HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback() - */ - - /* Stop UART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream */ - if (huart->hdmatx != NULL) - { - HAL_DMA_Abort(huart->hdmatx); - } - UART_EndTxTransfer(huart); - } - - /* Stop UART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream */ - if (huart->hdmarx != NULL) - { - HAL_DMA_Abort(huart->hdmarx); - } - UART_EndRxTransfer(huart); - } - - return HAL_OK; -} - -/** - * @brief Receive an amount of data in blocking mode till either the expected number of data is received or an IDLE event occurs. - * @note HAL_OK is returned if reception is completed (expected number of data has been received) - * or if reception is stopped after IDLE event (less than the expected number of data has been received) - * In this case, RxLen output parameter indicates number of data available in reception buffer. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @param RxLen Number of data elements finally received (could be lower than Size, in case reception ends on IDLE event) - * @param Timeout Timeout duration expressed in ms (covers the whole reception sequence). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, - uint32_t Timeout) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - uint32_t tickstart; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - __HAL_UNLOCK(huart); - - /* Initialize output number of received elements */ - *RxLen = 0U; - - /* as long as data have to be received */ - while (huart->RxXferCount > 0U) - { - /* Check if IDLE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) - { - /* Clear IDLE flag in ISR */ - __HAL_UART_CLEAR_IDLEFLAG(huart); - - /* If Set, but no data ever received, clear flag without exiting loop */ - /* If Set, and data has already been received, this means Idle Event is valid : End reception */ - if (*RxLen > 0U) - { - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - } - - /* Check if RXNE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RXNE)) - { - if (pdata8bits == NULL) - { - *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); - pdata16bits++; - } - else - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - - pdata8bits++; - } - /* Increment number of received elements */ - *RxLen += 1U; - huart->RxXferCount--; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - huart->RxState = HAL_UART_STATE_READY; - - return HAL_TIMEOUT; - } - } - } - - /* Set number of received elements in output parameter : RxLen */ - *RxLen = huart->RxXferSize - huart->RxXferCount; - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in interrupt mode till either the expected number of data is received or an IDLE event occurs. - * @note Reception is initiated by this function call. Further progress of reception is achieved thanks - * to UART interrupts raised by RXNE and IDLE events. Callback is called at end of reception indicating - * number of received data elements. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef status; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - /* Set Reception type to reception till IDLE Event*/ - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - status = UART_Start_Receive_IT(huart, pData, Size); - - /* Check Rx process has been successfully started */ - if (status == HAL_OK) - { - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - else - { - /* In case of errors already pending when reception is started, - Interrupts may have already been raised and lead to reception abortion. - (Overrun error for instance). - In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ - status = HAL_ERROR; - } - } - - return status; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in DMA mode till either the expected number of data is received or an IDLE event occurs. - * @note Reception is initiated by this function call. Further progress of reception is achieved thanks - * to DMA services, transferring automatically received data elements in user reception buffer and - * calling registered callbacks at half/end of reception. UART IDLE events are also used to consider - * reception phase as ended. In all cases, callback execution will indicate number of received data elements. - * @note When the UART parity is enabled (PCE = 1), the received data contain - * the parity bit (MSB position). - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef status; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - /* Set Reception type to reception till IDLE Event*/ - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - status = UART_Start_Receive_DMA(huart, pData, Size); - - /* Check Rx process has been successfully started */ - if (status == HAL_OK) - { - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - else - { - /* In case of errors already pending when reception is started, - Interrupts may have already been raised and lead to reception abortion. - (Overrun error for instance). - In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ - status = HAL_ERROR; - } - } - - return status; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort ongoing transfers (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx and Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream: use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream: use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Tx and Rx transfer counters */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->RxState and huart->gState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->gState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfers (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx and Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart) -{ - uint32_t AbortCplt = 0x01U; - - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* If DMA Tx and/or DMA Rx Handles are associated to UART Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (huart->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - huart->hdmatx->XferAbortCallback = UART_DMATxAbortCallback; - } - else - { - huart->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (huart->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - huart->hdmarx->XferAbortCallback = UART_DMARxAbortCallback; - } - else - { - huart->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - /* Disable DMA Tx at UART level */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use non blocking DMA Abort API (callback) */ - if (huart->hdmatx != NULL) - { - /* UART Tx DMA Abort callback has already been initialised : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) - { - huart->hdmatx->XferAbortCallback = NULL; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use non blocking DMA Abort API (callback) */ - if (huart->hdmarx != NULL) - { - /* UART Rx DMA Abort callback has already been initialised : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - huart->hdmarx->XferAbortCallback = NULL; - AbortCplt = 0x01U; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ - if (AbortCplt == 0x01U) - { - /* Reset Tx and Rx transfer counters */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = UART_DMATxOnlyAbortCallback; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) - { - /* Call Directly huart->hdmatx->XferAbortCallback function in case of error */ - huart->hdmatx->XferAbortCallback(huart->hdmatx); - } - } - else - { - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = UART_DMARxOnlyAbortCallback; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ - huart->hdmarx->XferAbortCallback(huart->hdmarx); - } - } - else - { - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief This function handles UART interrupt request. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) -{ - uint32_t isrflags = READ_REG(huart->Instance->SR); - uint32_t cr1its = READ_REG(huart->Instance->CR1); - uint32_t cr3its = READ_REG(huart->Instance->CR3); - uint32_t errorflags = 0x00U; - uint32_t dmarequest = 0x00U; - - /* If no error occurs */ - errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); - if (errorflags == RESET) - { - /* UART in mode Receiver -------------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - UART_Receive_IT(huart); - return; - } - } - - /* If some errors occur */ - if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) - || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) - { - /* UART parity error interrupt occurred ----------------------------------*/ - if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_PE; - } - - /* UART noise error interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_NE; - } - - /* UART frame error interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_FE; - } - - /* UART Over-Run interrupt occurred --------------------------------------*/ - if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) - || ((cr3its & USART_CR3_EIE) != RESET))) - { - huart->ErrorCode |= HAL_UART_ERROR_ORE; - } - - /* Call UART Error Call back function if need be --------------------------*/ - if (huart->ErrorCode != HAL_UART_ERROR_NONE) - { - /* UART in mode Receiver -----------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - UART_Receive_IT(huart); - } - - /* If Overrun error occurs, or if any error occurs in DMA mode reception, - consider error as blocking */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if (((huart->ErrorCode & HAL_UART_ERROR_ORE) != RESET) || dmarequest) - { - /* Blocking error : transfer is aborted - Set the UART state ready to be able to start again the process, - Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ - UART_EndRxTransfer(huart); - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - huart->hdmarx->XferAbortCallback(huart->hdmarx); - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Non Blocking error : transfer could go on. - Error is notified to user through user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - - huart->ErrorCode = HAL_UART_ERROR_NONE; - } - } - return; - } /* End if some error occurs */ - - /* Check current reception Mode : - If Reception till IDLE event has been selected : */ - if ((huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - && ((isrflags & USART_SR_IDLE) != 0U) - && ((cr1its & USART_SR_IDLE) != 0U)) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - - /* Check if DMA mode is enabled in UART */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - /* DMA mode enabled */ - /* Check received length : If all expected data are received, do nothing, - (DMA cplt callback will be called). - Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ - uint16_t nb_remaining_rx_data = (uint16_t) __HAL_DMA_GET_COUNTER(huart->hdmarx); - if ((nb_remaining_rx_data > 0U) - && (nb_remaining_rx_data < huart->RxXferSize)) - { - /* Reception is not complete */ - huart->RxXferCount = nb_remaining_rx_data; - - /* In Normal mode, end DMA xfer and HAL UART Rx process*/ - if (huart->hdmarx->Init.Mode != DMA_CIRCULAR) - { - /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by resetting the DMAR bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - - /* Last bytes received, so no need as the abort is immediate */ - (void)HAL_DMA_Abort(huart->hdmarx); - } -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - return; - } - else - { - /* DMA mode not enabled */ - /* Check received length : If all expected data are received, do nothing. - Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ - uint16_t nb_rx_data = huart->RxXferSize - huart->RxXferCount; - if ((huart->RxXferCount > 0U) - && (nb_rx_data > 0U)) - { - /* Disable the UART Parity Error Interrupt and RXNE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - - /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Rx process is completed, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxEventCallback(huart, nb_rx_data); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, nb_rx_data); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - return; - } - } - - /* UART in mode Transmitter ------------------------------------------------*/ - if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) - { - UART_Transmit_IT(huart); - return; - } - - /* UART in mode Transmitter end --------------------------------------------*/ - if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) - { - UART_EndTransmit_IT(huart); - return; - } -} - -/** - * @brief Tx Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief UART error callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief UART Abort Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief UART Abort Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortTransmitCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief UART Abort Receive Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortReceiveCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Reception Event Callback (Rx event notification called after use of advanced reception service). - * @param huart UART handle - * @param Size Number of data available in application reception buffer (indicates a position in - * reception buffer until which, data are available) - * @retval None - */ -__weak void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - UNUSED(Size); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UARTEx_RxEventCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group3 Peripheral Control functions - * @brief UART control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the UART: - (+) HAL_LIN_SendBreak() API can be helpful to transmit the break character. - (+) HAL_MultiProcessor_EnterMuteMode() API can be helpful to enter the UART in mute mode. - (+) HAL_MultiProcessor_ExitMuteMode() API can be helpful to exit the UART mute mode by software. - (+) HAL_HalfDuplex_EnableTransmitter() API to enable the UART transmitter and disables the UART receiver in Half Duplex mode - (+) HAL_HalfDuplex_EnableReceiver() API to enable the UART receiver and disables the UART transmitter in Half Duplex mode - -@endverbatim - * @{ - */ - -/** - * @brief Transmits break characters. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Send break characters */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_SBK); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enters the UART in mute mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_RWU); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Exits the UART mute mode: wake up software. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_RWU); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enables the UART transmitter and disables the UART receiver. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = huart->Instance->CR1; - - /* Clear TE and RE bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); - - /* Enable the USART's transmit interface by setting the TE bit in the USART CR1 register */ - tmpreg |= (uint32_t)USART_CR1_TE; - - /* Write to USART CR1 */ - WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enables the UART receiver and disables the UART transmitter. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = huart->Instance->CR1; - - /* Clear TE and RE bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); - - /* Enable the USART's receive interface by setting the RE bit in the USART CR1 register */ - tmpreg |= (uint32_t)USART_CR1_RE; - - /* Write to USART CR1 */ - WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group4 Peripheral State and Errors functions - * @brief UART State and Errors functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Errors functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to return the State of - UART communication process, return Peripheral Errors occurred during communication - process - (+) HAL_UART_GetState() API can be helpful to check in run-time the state of the UART peripheral. - (+) HAL_UART_GetError() check in run-time errors that could be occurred during communication. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the UART state. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL state - */ -HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart) -{ - uint32_t temp1 = 0x00U, temp2 = 0x00U; - temp1 = huart->gState; - temp2 = huart->RxState; - - return (HAL_UART_StateTypeDef)(temp1 | temp2); -} - -/** - * @brief Return the UART error code - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART. - * @retval UART Error Code - */ -uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart) -{ - return huart->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup UART_Private_Functions UART Private Functions - * @{ - */ - -/** - * @brief Initialize the callbacks to their default values. - * @param huart UART handle. - * @retval none - */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart) -{ - /* Init the UART Callback settings */ - huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ - huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak RxEventCallback */ - -} -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @brief DMA UART transmit process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode*/ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - huart->TxXferCount = 0x00U; - - /* Disable the DMA transfer for transmit request by setting the DMAT bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Enable the UART Transmit Complete Interrupt */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_TCIE); - - } - /* DMA Circular mode */ - else - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART transmit process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxHalfCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxHalfCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART receive process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode*/ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - huart->RxXferCount = 0U; - - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by setting the DMAR bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - /* If Reception till IDLE event has been selected, Disable IDLE Interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - } - - /* Check current reception Mode : - If Reception till IDLE event has been selected : use Rx Event callback */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* In other cases : use Rx Complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxCpltCallback(huart); -#else - /*Call legacy weak Rx complete callback*/ - HAL_UART_RxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART receive process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Check current reception Mode : - If Reception till IDLE event has been selected : use Rx Event callback */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize / 2U); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize / 2U); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* In other cases : use Rx Half Complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Half complete callback*/ - huart->RxHalfCpltCallback(huart); -#else - /*Call legacy weak Rx Half complete callback*/ - HAL_UART_RxHalfCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART communication error callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t dmarequest = 0x00U; - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Stop UART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - huart->TxXferCount = 0x00U; - UART_EndTxTransfer(huart); - } - - /* Stop UART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - huart->RxXferCount = 0x00U; - UART_EndRxTransfer(huart); - } - - huart->ErrorCode |= HAL_UART_ERROR_DMA; -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief This function handles UART Communication Timeout. It waits - * until a flag is no longer in the specified status. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param Flag specifies the UART flag to check. - * @param Status The actual Flag status (SET or RESET). - * @param Tickstart Tick start value - * @param Timeout Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is set */ - while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief Start Receive operation in interrupt mode. - * @note This function could be called by all HAL UART API providing reception in Interrupt mode. - * @note When calling this function, parameters validity is considered as already checked, - * i.e. Rx State, buffer address, ... - * UART Handle is assumed as Locked. - * @param huart UART handle. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - huart->pRxBuffPtr = pData; - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - if (huart->Init.Parity != UART_PARITY_NONE) - { - /* Enable the UART Parity Error Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_PE); - } - - /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - __HAL_UART_ENABLE_IT(huart, UART_IT_ERR); - - /* Enable the UART Data Register not empty Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_RXNE); - - return HAL_OK; -} - -/** - * @brief Start Receive operation in DMA mode. - * @note This function could be called by all HAL UART API providing reception in DMA mode. - * @note When calling this function, parameters validity is considered as already checked, - * i.e. Rx State, buffer address, ... - * UART Handle is assumed as Locked. - * @param huart UART handle. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - huart->pRxBuffPtr = pData; - huart->RxXferSize = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - - /* Set the UART DMA transfer complete callback */ - huart->hdmarx->XferCpltCallback = UART_DMAReceiveCplt; - - /* Set the UART DMA Half transfer complete callback */ - huart->hdmarx->XferHalfCpltCallback = UART_DMARxHalfCplt; - - /* Set the DMA error callback */ - huart->hdmarx->XferErrorCallback = UART_DMAError; - - /* Set the DMA abort callback */ - huart->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - tmp = (uint32_t *)&pData; - HAL_DMA_Start_IT(huart->hdmarx, (uint32_t)&huart->Instance->DR, *(uint32_t *)tmp, Size); - - /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ - __HAL_UART_CLEAR_OREFLAG(huart); - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - if (huart->Init.Parity != UART_PARITY_NONE) - { - /* Enable the UART Parity Error Interrupt */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); - } - - /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the UART CR3 register */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - return HAL_OK; -} - -/** - * @brief End ongoing Tx transfer on UART peripheral (following error detection or Transmit completion). - * @param huart UART handle. - * @retval None - */ -static void UART_EndTxTransfer(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* At end of Tx process, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; -} - -/** - * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion). - * @param huart UART handle. - * @retval None - */ -static void UART_EndRxTransfer(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* In case of reception waiting for IDLE event, disable also the IDLE IE interrupt source */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; -} - -/** - * @brief DMA UART communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - huart->RxXferCount = 0x00U; - huart->TxXferCount = 0x00U; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->hdmatx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (huart->hdmarx != NULL) - { - if (huart->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->hdmarx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (huart->hdmatx != NULL) - { - if (huart->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Tx communication abort callback, when initiated by user by a call to - * HAL_UART_AbortTransmit_IT API (Abort only Tx transfer) - * (This callback is executed at end of DMA Tx Abort procedure following user abort request, - * and leads to user Tx Abort Complete callback execution). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Rx communication abort callback, when initiated by user by a call to - * HAL_UART_AbortReceive_IT API (Abort only Rx transfer) - * (This callback is executed at end of DMA Rx Abort procedure following user abort request, - * and leads to user Rx Abort Complete callback execution). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief Sends an amount of data in non blocking mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart) -{ - const uint16_t *tmp; - - /* Check that a Tx process is ongoing */ - if (huart->gState == HAL_UART_STATE_BUSY_TX) - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - tmp = (const uint16_t *) huart->pTxBuffPtr; - huart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); - huart->pTxBuffPtr += 2U; - } - else - { - huart->Instance->DR = (uint8_t)(*huart->pTxBuffPtr++ & (uint8_t)0x00FF); - } - - if (--huart->TxXferCount == 0U) - { - /* Disable the UART Transmit Data Register Empty Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_TXE); - - /* Enable the UART Transmit Complete Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_TC); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Wraps up transmission in non blocking mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart) -{ - /* Disable the UART Transmit Complete Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_TC); - - /* Tx process is ended, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - - return HAL_OK; -} - -/** - * @brief Receives an amount of data in non blocking mode - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - - /* Check that a Rx process is ongoing */ - if (huart->RxState == HAL_UART_STATE_BUSY_RX) - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) huart->pRxBuffPtr; - *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); - huart->pRxBuffPtr += 2U; - } - else - { - pdata8bits = (uint8_t *) huart->pRxBuffPtr; - pdata16bits = NULL; - - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - huart->pRxBuffPtr += 1U; - } - - if (--huart->RxXferCount == 0U) - { - /* Disable the UART Data Register not empty Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_RXNE); - - /* Disable the UART Parity Error Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_PE); - - /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - __HAL_UART_DISABLE_IT(huart, UART_IT_ERR); - - /* Rx process is completed, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - /* Check current reception Mode : - If Reception till IDLE event has been selected : */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - /* Set reception type to Standard */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Disable IDLE interrupt */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - - /* Check if IDLE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) - { - /* Clear IDLE flag in ISR */ - __HAL_UART_CLEAR_IDLEFLAG(huart); - } - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* Standard reception API called */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxCpltCallback(huart); -#else - /*Call legacy weak Rx complete callback*/ - HAL_UART_RxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures the UART peripheral. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -static void UART_SetConfig(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg; - uint32_t pclk; - - /* Check the parameters */ - assert_param(IS_UART_BAUDRATE(huart->Init.BaudRate)); - assert_param(IS_UART_STOPBITS(huart->Init.StopBits)); - assert_param(IS_UART_PARITY(huart->Init.Parity)); - assert_param(IS_UART_MODE(huart->Init.Mode)); - - /*-------------------------- USART CR2 Configuration -----------------------*/ - /* Configure the UART Stop Bits: Set STOP[13:12] bits - according to huart->Init.StopBits value */ - MODIFY_REG(huart->Instance->CR2, USART_CR2_STOP, huart->Init.StopBits); - - /*-------------------------- USART CR1 Configuration -----------------------*/ - /* Configure the UART Word Length, Parity and mode: - Set the M bits according to huart->Init.WordLength value - Set PCE and PS bits according to huart->Init.Parity value - Set TE and RE bits according to huart->Init.Mode value - Set OVER8 bit according to huart->Init.OverSampling value */ - - tmpreg = (uint32_t)huart->Init.WordLength | huart->Init.Parity | huart->Init.Mode | huart->Init.OverSampling; - MODIFY_REG(huart->Instance->CR1, - (uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), - tmpreg); - - /*-------------------------- USART CR3 Configuration -----------------------*/ - /* Configure the UART HFC: Set CTSE and RTSE bits according to huart->Init.HwFlowCtl value */ - MODIFY_REG(huart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE), huart->Init.HwFlowCtl); - - -#if defined(USART6) && defined(UART9) && defined(UART10) - if ((huart->Instance == USART1) || (huart->Instance == USART6) || (huart->Instance == UART9) || (huart->Instance == UART10)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#elif defined(USART6) - if ((huart->Instance == USART1) || (huart->Instance == USART6)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#else - if (huart->Instance == USART1) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#endif /* USART6 */ - else - { - pclk = HAL_RCC_GetPCLK1Freq(); - } - /*-------------------------- USART BRR Configuration ---------------------*/ - if (huart->Init.OverSampling == UART_OVERSAMPLING_8) - { - huart->Instance->BRR = UART_BRR_SAMPLING8(pclk, huart->Init.BaudRate); - } - else - { - huart->Instance->BRR = UART_BRR_SAMPLING16(pclk, huart->Init.BaudRate); - } -} - -/** - * @} - */ - -#endif /* HAL_UART_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - +/** + ****************************************************************************** + * @file stm32f4xx_hal_uart.c + * @author MCD Application Team + * @brief UART HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Universal Asynchronous Receiver Transmitter Peripheral (UART). + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The UART HAL driver can be used as follows: + + (#) Declare a UART_HandleTypeDef handle structure (eg. UART_HandleTypeDef huart). + (#) Initialize the UART low level resources by implementing the HAL_UART_MspInit() API: + (##) Enable the USARTx interface clock. + (##) UART pins configuration: + (+++) Enable the clock for the UART GPIOs. + (+++) Configure the UART TX/RX pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_UART_Transmit_IT() + and HAL_UART_Receive_IT() APIs): + (+++) Configure the USARTx interrupt priority. + (+++) Enable the NVIC USART IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_UART_Transmit_DMA() + and HAL_UART_Receive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required + Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx stream. + (+++) Associate the initialized DMA handle to the UART DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the DMA Tx/Rx stream. + (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle + (used for last byte sending completion detection in DMA non circular mode) + + (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware + flow control and Mode(Receiver/Transmitter) in the huart Init structure. + + (#) For the UART asynchronous mode, initialize the UART registers by calling + the HAL_UART_Init() API. + + (#) For the UART Half duplex mode, initialize the UART registers by calling + the HAL_HalfDuplex_Init() API. + + (#) For the LIN mode, initialize the UART registers by calling the HAL_LIN_Init() API. + + (#) For the Multi-Processor mode, initialize the UART registers by calling + the HAL_MultiProcessor_Init() API. + + [..] + (@) The specific UART interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_UART_ENABLE_IT() and __HAL_UART_DISABLE_IT() inside the transmit + and receive process. + + [..] + (@) These APIs (HAL_UART_Init() and HAL_HalfDuplex_Init()) configure also the + low level Hardware GPIO, CLOCK, CORTEX...etc) by calling the customized + HAL_UART_MspInit() API. + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_UART_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_UART_RegisterCallback() to register a user callback. + Function HAL_UART_RegisterCallback() allows to register following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : UART MspInit. + (+) MspDeInitCallback : UART MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_UART_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : UART MspInit. + (+) MspDeInitCallback : UART MspDeInit. + + [..] + For specific callback RxEventCallback, use dedicated registration/reset functions: + respectively HAL_UART_RegisterRxEventCallback() , HAL_UART_UnRegisterRxEventCallback(). + + [..] + By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_UART_Init() + and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_UART_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_UART_STATE_READY or HAL_UART_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_UART_RegisterCallback() before calling HAL_UART_DeInit() + or HAL_UART_Init() function. + + [..] + When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + [..] + Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_UART_Transmit() + (+) Receive an amount of data in blocking mode using HAL_UART_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_UART_Transmit_IT() + (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_UART_Receive_IT() + (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxCpltCallback + (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_UART_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_UART_Transmit_DMA() + (+) At transmission end of half transfer HAL_UART_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxHalfCpltCallback + (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_UART_Receive_DMA() + (+) At reception end of half transfer HAL_UART_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxHalfCpltCallback + (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxCpltCallback + (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_UART_ErrorCallback + (+) Pause the DMA Transfer using HAL_UART_DMAPause() + (+) Resume the DMA Transfer using HAL_UART_DMAResume() + (+) Stop the DMA Transfer using HAL_UART_DMAStop() + + + [..] This subsection also provides a set of additional functions providing enhanced reception + services to user. (For example, these functions allow application to handle use cases + where number of data to be received is unknown). + + (#) Compared to standard reception services which only consider number of received + data elements as reception completion criteria, these functions also consider additional events + as triggers for updating reception status to caller : + (+) Detection of inactivity period (RX line has not been active for a given period). + (++) RX inactivity detected by IDLE event, i.e. RX line has been in idle state (normally high state) + for 1 frame time, after last received byte. + + (#) There are two mode of transfer: + (+) Blocking mode: The reception is performed in polling mode, until either expected number of data is received, + or till IDLE event occurs. Reception is handled only during function execution. + When function exits, no data reception could occur. HAL status and number of actually received data elements, + are returned by function after finishing transfer. + (+) Non-Blocking mode: The reception is performed using Interrupts or DMA. + These API's return the HAL status. + The end of the data processing will be indicated through the + dedicated UART IRQ when using Interrupt mode or the DMA IRQ when using DMA mode. + The HAL_UARTEx_RxEventCallback() user callback will be executed during Receive process + The HAL_UART_ErrorCallback()user callback will be executed when a reception error is detected. + + (#) Blocking mode API: + (+) HAL_UARTEx_ReceiveToIdle() + + (#) Non-Blocking mode API with Interrupt: + (+) HAL_UARTEx_ReceiveToIdle_IT() + + (#) Non-Blocking mode API with DMA: + (+) HAL_UARTEx_ReceiveToIdle_DMA() + + + *** UART HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in UART HAL driver. + + (+) __HAL_UART_ENABLE: Enable the UART peripheral + (+) __HAL_UART_DISABLE: Disable the UART peripheral + (+) __HAL_UART_GET_FLAG : Check whether the specified UART flag is set or not + (+) __HAL_UART_CLEAR_FLAG : Clear the specified UART pending flag + (+) __HAL_UART_ENABLE_IT: Enable the specified UART interrupt + (+) __HAL_UART_DISABLE_IT: Disable the specified UART interrupt + (+) __HAL_UART_GET_IT_SOURCE: Check whether the specified UART interrupt has occurred or not + + [..] + (@) You can refer to the UART HAL driver header file for more useful macros + + @endverbatim + [..] + (@) Additional remark: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible UART frame formats are as listed in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | UART frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup UART UART + * @brief HAL UART module driver + * @{ + */ +#ifdef HAL_UART_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup UART_Private_Constants + * @{ + */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup UART_Private_Functions UART Private Functions + * @{ + */ + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +static void UART_EndTxTransfer(UART_HandleTypeDef *huart); +static void UART_EndRxTransfer(UART_HandleTypeDef *huart); +static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); +static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void UART_DMAError(DMA_HandleTypeDef *hdma); +static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout); +static void UART_SetConfig(UART_HandleTypeDef *huart); + +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ +/** @defgroup UART_Exported_Functions UART Exported Functions + * @{ + */ + +/** @defgroup UART_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USARTx or the UARTy + in asynchronous mode. + (+) For the asynchronous mode only these parameters can be configured: + (++) Baud Rate + (++) Word Length + (++) Stop Bit + (++) Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + please refer to Reference manual for possible UART frame formats. + (++) Hardware flow control + (++) Receiver/transmitter modes + (++) Over Sampling Method + [..] + The HAL_UART_Init(), HAL_HalfDuplex_Init(), HAL_LIN_Init() and HAL_MultiProcessor_Init() APIs + follow respectively the UART asynchronous, UART Half duplex, LIN and Multi-Processor configuration + procedures (details for the procedures are available in reference manual + (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs + RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs + RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs + RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the UART mode according to the specified parameters in + * the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + if (huart->Init.HwFlowCtl != UART_HWCONTROL_NONE) + { + /* The hardware flow control is available only for USART1, USART2, USART3 and USART6. + Except for STM32F446xx devices, that is available for USART1, USART2, USART3, USART6, UART4 and UART5. + */ + assert_param(IS_UART_HWFLOW_INSTANCE(huart->Instance)); + assert_param(IS_UART_HARDWARE_FLOW_CONTROL(huart->Init.HwFlowCtl)); + } + else + { + assert_param(IS_UART_INSTANCE(huart->Instance)); + } + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In asynchronous mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the half-duplex mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_HALFDUPLEX_INSTANCE(huart->Instance)); + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In half-duplex mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_IREN | USART_CR3_SCEN)); + + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + SET_BIT(huart->Instance->CR3, USART_CR3_HDSEL); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state*/ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the LIN mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param BreakDetectLength Specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg UART_LINBREAKDETECTLENGTH_10B: 10-bit break detection + * @arg UART_LINBREAKDETECTLENGTH_11B: 11-bit break detection + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the LIN UART instance */ + assert_param(IS_UART_LIN_INSTANCE(huart->Instance)); + + /* Check the Break detection length parameter */ + assert_param(IS_UART_LIN_BREAK_DETECT_LENGTH(BreakDetectLength)); + assert_param(IS_UART_LIN_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_LIN_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In LIN mode, the following bits must be kept cleared: + - CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_HDSEL | USART_CR3_IREN | USART_CR3_SCEN)); + + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + SET_BIT(huart->Instance->CR2, USART_CR2_LINEN); + + /* Set the USART LIN Break detection length. */ + CLEAR_BIT(huart->Instance->CR2, USART_CR2_LBDL); + SET_BIT(huart->Instance->CR2, BreakDetectLength); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state*/ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the Multi-Processor mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param Address USART address + * @param WakeUpMethod specifies the USART wake-up method. + * This parameter can be one of the following values: + * @arg UART_WAKEUPMETHOD_IDLELINE: Wake-up by an idle line detection + * @arg UART_WAKEUPMETHOD_ADDRESSMARK: Wake-up by an address mark + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Check the Address & wake up method parameters */ + assert_param(IS_UART_WAKEUPMETHOD(WakeUpMethod)); + assert_param(IS_UART_ADDRESS(Address)); + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In Multi-Processor mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register */ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + + /* Set the USART address node */ + CLEAR_BIT(huart->Instance->CR2, USART_CR2_ADD); + SET_BIT(huart->Instance->CR2, Address); + + /* Set the wake up method by setting the WAKE bit in the CR1 register */ + CLEAR_BIT(huart->Instance->CR1, USART_CR1_WAKE); + SET_BIT(huart->Instance->CR1, WakeUpMethod); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the UART peripheral. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_UART_DISABLE(huart); + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + if (huart->MspDeInitCallback == NULL) + { + huart->MspDeInitCallback = HAL_UART_MspDeInit; + } + /* DeInit the low level hardware */ + huart->MspDeInitCallback(huart); +#else + /* DeInit the low level hardware */ + HAL_UART_MspDeInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_RESET; + huart->RxState = HAL_UART_STATE_RESET; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Process Unlock */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief UART MSP Init. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_MspInit(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_MspInit could be implemented in the user file + */ +} + +/** + * @brief UART MSP DeInit. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_MspDeInit(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User UART Callback + * To be used instead of the weak predefined callback + * @param huart uart handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, + pUART_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + switch (CallbackID) + { + case HAL_UART_TX_HALFCOMPLETE_CB_ID : + huart->TxHalfCpltCallback = pCallback; + break; + + case HAL_UART_TX_COMPLETE_CB_ID : + huart->TxCpltCallback = pCallback; + break; + + case HAL_UART_RX_HALFCOMPLETE_CB_ID : + huart->RxHalfCpltCallback = pCallback; + break; + + case HAL_UART_RX_COMPLETE_CB_ID : + huart->RxCpltCallback = pCallback; + break; + + case HAL_UART_ERROR_CB_ID : + huart->ErrorCallback = pCallback; + break; + + case HAL_UART_ABORT_COMPLETE_CB_ID : + huart->AbortCpltCallback = pCallback; + break; + + case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : + huart->AbortTransmitCpltCallback = pCallback; + break; + + case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : + huart->AbortReceiveCpltCallback = pCallback; + break; + + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = pCallback; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (huart->gState == HAL_UART_STATE_RESET) + { + switch (CallbackID) + { + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = pCallback; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief Unregister an UART Callback + * UART callaback is redirected to the weak predefined callback + * @param huart uart handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(huart); + + if (HAL_UART_STATE_READY == huart->gState) + { + switch (CallbackID) + { + case HAL_UART_TX_HALFCOMPLETE_CB_ID : + huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_UART_TX_COMPLETE_CB_ID : + huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_UART_RX_HALFCOMPLETE_CB_ID : + huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_UART_RX_COMPLETE_CB_ID : + huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_UART_ERROR_CB_ID : + huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_UART_ABORT_COMPLETE_CB_ID : + huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : + huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + break; + + case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : + huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + break; + + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = HAL_UART_MspInit; /* Legacy weak MspInitCallback */ + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = HAL_UART_MspDeInit; /* Legacy weak MspDeInitCallback */ + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_UART_STATE_RESET == huart->gState) + { + switch (CallbackID) + { + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = HAL_UART_MspInit; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = HAL_UART_MspDeInit; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief Register a User UART Rx Event Callback + * To be used instead of the weak predefined callback + * @param huart Uart handle + * @param pCallback Pointer to the Rx Event Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + huart->RxEventCallback = pCallback; + } + else + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief UnRegister the UART Rx Event Callback + * UART Rx Event Callback is redirected to the weak HAL_UARTEx_RxEventCallback() predefined callback + * @param huart Uart handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */ + } + else + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + return status; +} +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group2 IO operation functions + * @brief UART Transmit and Receive functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + This subsection provides a set of functions allowing to manage the UART asynchronous + and Half duplex data transfers. + + (#) There are two modes of transfer: + (+) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (+) Non-Blocking mode: The communication is performed using Interrupts + or DMA, these API's return the HAL status. + The end of the data processing will be indicated through the + dedicated UART IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_UART_TxCpltCallback(), HAL_UART_RxCpltCallback() user callbacks + will be executed respectively at the end of the transmit or receive process + The HAL_UART_ErrorCallback()user callback will be executed when a communication error is detected. + + (#) Blocking mode API's are : + (+) HAL_UART_Transmit() + (+) HAL_UART_Receive() + + (#) Non-Blocking mode API's with Interrupt are : + (+) HAL_UART_Transmit_IT() + (+) HAL_UART_Receive_IT() + (+) HAL_UART_IRQHandler() + + (#) Non-Blocking mode API's with DMA are : + (+) HAL_UART_Transmit_DMA() + (+) HAL_UART_Receive_DMA() + (+) HAL_UART_DMAPause() + (+) HAL_UART_DMAResume() + (+) HAL_UART_DMAStop() + + (#) A set of Transfer Complete Callbacks are provided in Non_Blocking mode: + (+) HAL_UART_TxHalfCpltCallback() + (+) HAL_UART_TxCpltCallback() + (+) HAL_UART_RxHalfCpltCallback() + (+) HAL_UART_RxCpltCallback() + (+) HAL_UART_ErrorCallback() + + (#) Non-Blocking mode transfers could be aborted using Abort API's : + (+) HAL_UART_Abort() + (+) HAL_UART_AbortTransmit() + (+) HAL_UART_AbortReceive() + (+) HAL_UART_Abort_IT() + (+) HAL_UART_AbortTransmit_IT() + (+) HAL_UART_AbortReceive_IT() + + (#) For Abort services based on interrupts (HAL_UART_Abortxxx_IT), a set of Abort Complete Callbacks are provided: + (+) HAL_UART_AbortCpltCallback() + (+) HAL_UART_AbortTransmitCpltCallback() + (+) HAL_UART_AbortReceiveCpltCallback() + + (#) A Rx Event Reception Callback (Rx event notification) is available for Non_Blocking modes of enhanced reception services: + (+) HAL_UARTEx_RxEventCallback() + + (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. + Errors are handled as follows : + (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is + to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . + Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, + and HAL_UART_ErrorCallback() user callback is executed. Transfer is kept ongoing on UART side. + If user wants to abort it, Abort services should be called by user. + (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. + This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. + Error code is set to allow user to identify error type, and HAL_UART_ErrorCallback() user callback is executed. + + -@- In the Half duplex communication, it is forbidden to run the transmit + and receive process in parallel, the UART state HAL_UART_STATE_BUSY_TX_RX can't be useful. + +@endverbatim + * @{ + */ + +/** + * @brief Sends an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + const uint8_t *pdata8bits; + const uint16_t *pdata16bits; + uint32_t tickstart = 0U; + + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (const uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + while (huart->TxXferCount > 0U) + { + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (pdata8bits == NULL) + { + huart->Instance->DR = (uint16_t)(*pdata16bits & 0x01FFU); + pdata16bits++; + } + else + { + huart->Instance->DR = (uint8_t)(*pdata8bits & 0xFFU); + pdata8bits++; + } + huart->TxXferCount--; + } + + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* At end of Tx process, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + uint32_t tickstart = 0U; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Check the remain data to be received */ + while (huart->RxXferCount > 0U) + { + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (pdata8bits == NULL) + { + *pdata16bits = (uint16_t)(huart->Instance->DR & 0x01FF); + pdata16bits++; + } + else + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + pdata8bits++; + } + huart->RxXferCount--; + } + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sends an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size) +{ + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->pTxBuffPtr = pData; + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the UART Transmit data register empty Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_TXE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + /* Set Reception type to Standard reception */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return (UART_Start_Receive_IT(huart, pData, Size)); + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sends an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size) +{ + const uint32_t *tmp; + + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->pTxBuffPtr = pData; + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Set the UART DMA transfer complete callback */ + huart->hdmatx->XferCpltCallback = UART_DMATransmitCplt; + + /* Set the UART DMA Half transfer complete callback */ + huart->hdmatx->XferHalfCpltCallback = UART_DMATxHalfCplt; + + /* Set the DMA error callback */ + huart->hdmatx->XferErrorCallback = UART_DMAError; + + /* Set the DMA abort callback */ + huart->hdmatx->XferAbortCallback = NULL; + + /* Enable the UART transmit DMA stream */ + tmp = (const uint32_t *)&pData; + HAL_DMA_Start_IT(huart->hdmatx, *(const uint32_t *)tmp, (uint32_t)&huart->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_UART_CLEAR_FLAG(huart, UART_FLAG_TC); + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the UART CR3 register */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @note When the UART parity is enabled (PCE = 1) the received data contains the parity bit. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + /* Set Reception type to Standard reception */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return (UART_Start_Receive_DMA(huart, pData, Size)); + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Pauses the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart) +{ + uint32_t dmarequest = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + /* Disable the UART DMA Tx request */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + } + + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the UART DMA Rx request */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Resumes the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart) +{ + /* Process Locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_BUSY_TX) + { + /* Enable the UART DMA Tx request */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); + } + + if (huart->RxState == HAL_UART_STATE_BUSY_RX) + { + /* Clear the Overrun flag before resuming the Rx transfer*/ + __HAL_UART_CLEAR_OREFLAG(huart); + + /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ + if (huart->Init.Parity != UART_PARITY_NONE) + { + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); + } + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Enable the UART DMA Rx request */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Stops the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart) +{ + uint32_t dmarequest = 0x00U; + /* The Lock is not implemented on this API to allow the user application + to call the HAL UART API under callbacks HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback() + */ + + /* Stop UART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream */ + if (huart->hdmatx != NULL) + { + HAL_DMA_Abort(huart->hdmatx); + } + UART_EndTxTransfer(huart); + } + + /* Stop UART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream */ + if (huart->hdmarx != NULL) + { + HAL_DMA_Abort(huart->hdmarx); + } + UART_EndRxTransfer(huart); + } + + return HAL_OK; +} + +/** + * @brief Receive an amount of data in blocking mode till either the expected number of data is received or an IDLE event occurs. + * @note HAL_OK is returned if reception is completed (expected number of data has been received) + * or if reception is stopped after IDLE event (less than the expected number of data has been received) + * In this case, RxLen output parameter indicates number of data available in reception buffer. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @param RxLen Number of data elements finally received (could be lower than Size, in case reception ends on IDLE event) + * @param Timeout Timeout duration expressed in ms (covers the whole reception sequence). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, + uint32_t Timeout) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + uint32_t tickstart; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + __HAL_UNLOCK(huart); + + /* Initialize output number of received elements */ + *RxLen = 0U; + + /* as long as data have to be received */ + while (huart->RxXferCount > 0U) + { + /* Check if IDLE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) + { + /* Clear IDLE flag in ISR */ + __HAL_UART_CLEAR_IDLEFLAG(huart); + + /* If Set, but no data ever received, clear flag without exiting loop */ + /* If Set, and data has already been received, this means Idle Event is valid : End reception */ + if (*RxLen > 0U) + { + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + } + + /* Check if RXNE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RXNE)) + { + if (pdata8bits == NULL) + { + *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); + pdata16bits++; + } + else + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + + pdata8bits++; + } + /* Increment number of received elements */ + *RxLen += 1U; + huart->RxXferCount--; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + huart->RxState = HAL_UART_STATE_READY; + + return HAL_TIMEOUT; + } + } + } + + /* Set number of received elements in output parameter : RxLen */ + *RxLen = huart->RxXferSize - huart->RxXferCount; + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in interrupt mode till either the expected number of data is received or an IDLE event occurs. + * @note Reception is initiated by this function call. Further progress of reception is achieved thanks + * to UART interrupts raised by RXNE and IDLE events. Callback is called at end of reception indicating + * number of received data elements. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef status; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + /* Set Reception type to reception till IDLE Event*/ + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + status = UART_Start_Receive_IT(huart, pData, Size); + + /* Check Rx process has been successfully started */ + if (status == HAL_OK) + { + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + else + { + /* In case of errors already pending when reception is started, + Interrupts may have already been raised and lead to reception abortion. + (Overrun error for instance). + In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ + status = HAL_ERROR; + } + } + + return status; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in DMA mode till either the expected number of data is received or an IDLE event occurs. + * @note Reception is initiated by this function call. Further progress of reception is achieved thanks + * to DMA services, transferring automatically received data elements in user reception buffer and + * calling registered callbacks at half/end of reception. UART IDLE events are also used to consider + * reception phase as ended. In all cases, callback execution will indicate number of received data elements. + * @note When the UART parity is enabled (PCE = 1), the received data contain + * the parity bit (MSB position). + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef status; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + /* Set Reception type to reception till IDLE Event*/ + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + status = UART_Start_Receive_DMA(huart, pData, Size); + + /* Check Rx process has been successfully started */ + if (status == HAL_OK) + { + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + else + { + /* In case of errors already pending when reception is started, + Interrupts may have already been raised and lead to reception abortion. + (Overrun error for instance). + In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ + status = HAL_ERROR; + } + } + + return status; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort ongoing transfers (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx and Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream: use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream: use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Tx and Rx transfer counters */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->RxState and huart->gState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->gState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfers (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx and Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart) +{ + uint32_t AbortCplt = 0x01U; + + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* If DMA Tx and/or DMA Rx Handles are associated to UART Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (huart->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + huart->hdmatx->XferAbortCallback = UART_DMATxAbortCallback; + } + else + { + huart->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (huart->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + huart->hdmarx->XferAbortCallback = UART_DMARxAbortCallback; + } + else + { + huart->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + /* Disable DMA Tx at UART level */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use non blocking DMA Abort API (callback) */ + if (huart->hdmatx != NULL) + { + /* UART Tx DMA Abort callback has already been initialised : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) + { + huart->hdmatx->XferAbortCallback = NULL; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use non blocking DMA Abort API (callback) */ + if (huart->hdmarx != NULL) + { + /* UART Rx DMA Abort callback has already been initialised : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + huart->hdmarx->XferAbortCallback = NULL; + AbortCplt = 0x01U; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ + if (AbortCplt == 0x01U) + { + /* Reset Tx and Rx transfer counters */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = UART_DMATxOnlyAbortCallback; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) + { + /* Call Directly huart->hdmatx->XferAbortCallback function in case of error */ + huart->hdmatx->XferAbortCallback(huart->hdmatx); + } + } + else + { + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = UART_DMARxOnlyAbortCallback; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ + huart->hdmarx->XferAbortCallback(huart->hdmarx); + } + } + else + { + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief This function handles UART interrupt request. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) +{ + uint32_t isrflags = READ_REG(huart->Instance->SR); + uint32_t cr1its = READ_REG(huart->Instance->CR1); + uint32_t cr3its = READ_REG(huart->Instance->CR3); + uint32_t errorflags = 0x00U; + uint32_t dmarequest = 0x00U; + + /* If no error occurs */ + errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); + if (errorflags == RESET) + { + /* UART in mode Receiver -------------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + UART_Receive_IT(huart); + return; + } + } + + /* If some errors occur */ + if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) + || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) + { + /* UART parity error interrupt occurred ----------------------------------*/ + if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_PE; + } + + /* UART noise error interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_NE; + } + + /* UART frame error interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_FE; + } + + /* UART Over-Run interrupt occurred --------------------------------------*/ + if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) + || ((cr3its & USART_CR3_EIE) != RESET))) + { + huart->ErrorCode |= HAL_UART_ERROR_ORE; + } + + /* Call UART Error Call back function if need be --------------------------*/ + if (huart->ErrorCode != HAL_UART_ERROR_NONE) + { + /* UART in mode Receiver -----------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + UART_Receive_IT(huart); + } + + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if (((huart->ErrorCode & HAL_UART_ERROR_ORE) != RESET) || dmarequest) + { + /* Blocking error : transfer is aborted + Set the UART state ready to be able to start again the process, + Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ + UART_EndRxTransfer(huart); + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + huart->hdmarx->XferAbortCallback(huart->hdmarx); + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Non Blocking error : transfer could go on. + Error is notified to user through user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + + huart->ErrorCode = HAL_UART_ERROR_NONE; + } + } + return; + } /* End if some error occurs */ + + /* Check current reception Mode : + If Reception till IDLE event has been selected : */ + if ((huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + && ((isrflags & USART_SR_IDLE) != 0U) + && ((cr1its & USART_SR_IDLE) != 0U)) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + + /* Check if DMA mode is enabled in UART */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + /* DMA mode enabled */ + /* Check received length : If all expected data are received, do nothing, + (DMA cplt callback will be called). + Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ + uint16_t nb_remaining_rx_data = (uint16_t) __HAL_DMA_GET_COUNTER(huart->hdmarx); + if ((nb_remaining_rx_data > 0U) + && (nb_remaining_rx_data < huart->RxXferSize)) + { + /* Reception is not complete */ + huart->RxXferCount = nb_remaining_rx_data; + + /* In Normal mode, end DMA xfer and HAL UART Rx process*/ + if (huart->hdmarx->Init.Mode != DMA_CIRCULAR) + { + /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by resetting the DMAR bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + + /* Last bytes received, so no need as the abort is immediate */ + (void)HAL_DMA_Abort(huart->hdmarx); + } +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + return; + } + else + { + /* DMA mode not enabled */ + /* Check received length : If all expected data are received, do nothing. + Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ + uint16_t nb_rx_data = huart->RxXferSize - huart->RxXferCount; + if ((huart->RxXferCount > 0U) + && (nb_rx_data > 0U)) + { + /* Disable the UART Parity Error Interrupt and RXNE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + + /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Rx process is completed, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxEventCallback(huart, nb_rx_data); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, nb_rx_data); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + return; + } + } + + /* UART in mode Transmitter ------------------------------------------------*/ + if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) + { + UART_Transmit_IT(huart); + return; + } + + /* UART in mode Transmitter end --------------------------------------------*/ + if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) + { + UART_EndTransmit_IT(huart); + return; + } +} + +/** + * @brief Tx Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief UART error callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief UART Abort Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief UART Abort Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortTransmitCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief UART Abort Receive Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortReceiveCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Reception Event Callback (Rx event notification called after use of advanced reception service). + * @param huart UART handle + * @param Size Number of data available in application reception buffer (indicates a position in + * reception buffer until which, data are available) + * @retval None + */ +__weak void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + UNUSED(Size); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UARTEx_RxEventCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group3 Peripheral Control functions + * @brief UART control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the UART: + (+) HAL_LIN_SendBreak() API can be helpful to transmit the break character. + (+) HAL_MultiProcessor_EnterMuteMode() API can be helpful to enter the UART in mute mode. + (+) HAL_MultiProcessor_ExitMuteMode() API can be helpful to exit the UART mute mode by software. + (+) HAL_HalfDuplex_EnableTransmitter() API to enable the UART transmitter and disables the UART receiver in Half Duplex mode + (+) HAL_HalfDuplex_EnableReceiver() API to enable the UART receiver and disables the UART transmitter in Half Duplex mode + +@endverbatim + * @{ + */ + +/** + * @brief Transmits break characters. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Send break characters */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_SBK); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enters the UART in mute mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_RWU); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Exits the UART mute mode: wake up software. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_RWU); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enables the UART transmitter and disables the UART receiver. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = huart->Instance->CR1; + + /* Clear TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); + + /* Enable the USART's transmit interface by setting the TE bit in the USART CR1 register */ + tmpreg |= (uint32_t)USART_CR1_TE; + + /* Write to USART CR1 */ + WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enables the UART receiver and disables the UART transmitter. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = huart->Instance->CR1; + + /* Clear TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); + + /* Enable the USART's receive interface by setting the RE bit in the USART CR1 register */ + tmpreg |= (uint32_t)USART_CR1_RE; + + /* Write to USART CR1 */ + WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group4 Peripheral State and Errors functions + * @brief UART State and Errors functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Errors functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to return the State of + UART communication process, return Peripheral Errors occurred during communication + process + (+) HAL_UART_GetState() API can be helpful to check in run-time the state of the UART peripheral. + (+) HAL_UART_GetError() check in run-time errors that could be occurred during communication. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the UART state. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL state + */ +HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart) +{ + uint32_t temp1 = 0x00U, temp2 = 0x00U; + temp1 = huart->gState; + temp2 = huart->RxState; + + return (HAL_UART_StateTypeDef)(temp1 | temp2); +} + +/** + * @brief Return the UART error code + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART. + * @retval UART Error Code + */ +uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart) +{ + return huart->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup UART_Private_Functions UART Private Functions + * @{ + */ + +/** + * @brief Initialize the callbacks to their default values. + * @param huart UART handle. + * @retval none + */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart) +{ + /* Init the UART Callback settings */ + huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ + huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak RxEventCallback */ + +} +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @brief DMA UART transmit process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode*/ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + huart->TxXferCount = 0x00U; + + /* Disable the DMA transfer for transmit request by setting the DMAT bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Enable the UART Transmit Complete Interrupt */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_TCIE); + + } + /* DMA Circular mode */ + else + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART transmit process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxHalfCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxHalfCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART receive process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode*/ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + huart->RxXferCount = 0U; + + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by setting the DMAR bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + /* If Reception till IDLE event has been selected, Disable IDLE Interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + } + + /* Check current reception Mode : + If Reception till IDLE event has been selected : use Rx Event callback */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* In other cases : use Rx Complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxCpltCallback(huart); +#else + /*Call legacy weak Rx complete callback*/ + HAL_UART_RxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART receive process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Check current reception Mode : + If Reception till IDLE event has been selected : use Rx Event callback */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize / 2U); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize / 2U); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* In other cases : use Rx Half Complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Half complete callback*/ + huart->RxHalfCpltCallback(huart); +#else + /*Call legacy weak Rx Half complete callback*/ + HAL_UART_RxHalfCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART communication error callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t dmarequest = 0x00U; + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Stop UART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + huart->TxXferCount = 0x00U; + UART_EndTxTransfer(huart); + } + + /* Stop UART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + huart->RxXferCount = 0x00U; + UART_EndRxTransfer(huart); + } + + huart->ErrorCode |= HAL_UART_ERROR_DMA; +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief This function handles UART Communication Timeout. It waits + * until a flag is no longer in the specified status. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param Flag specifies the UART flag to check. + * @param Status The actual Flag status (SET or RESET). + * @param Tickstart Tick start value + * @param Timeout Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is set */ + while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief Start Receive operation in interrupt mode. + * @note This function could be called by all HAL UART API providing reception in Interrupt mode. + * @note When calling this function, parameters validity is considered as already checked, + * i.e. Rx State, buffer address, ... + * UART Handle is assumed as Locked. + * @param huart UART handle. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + huart->pRxBuffPtr = pData; + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + if (huart->Init.Parity != UART_PARITY_NONE) + { + /* Enable the UART Parity Error Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_PE); + } + + /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + __HAL_UART_ENABLE_IT(huart, UART_IT_ERR); + + /* Enable the UART Data Register not empty Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_RXNE); + + return HAL_OK; +} + +/** + * @brief Start Receive operation in DMA mode. + * @note This function could be called by all HAL UART API providing reception in DMA mode. + * @note When calling this function, parameters validity is considered as already checked, + * i.e. Rx State, buffer address, ... + * UART Handle is assumed as Locked. + * @param huart UART handle. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + huart->pRxBuffPtr = pData; + huart->RxXferSize = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + + /* Set the UART DMA transfer complete callback */ + huart->hdmarx->XferCpltCallback = UART_DMAReceiveCplt; + + /* Set the UART DMA Half transfer complete callback */ + huart->hdmarx->XferHalfCpltCallback = UART_DMARxHalfCplt; + + /* Set the DMA error callback */ + huart->hdmarx->XferErrorCallback = UART_DMAError; + + /* Set the DMA abort callback */ + huart->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + tmp = (uint32_t *)&pData; + HAL_DMA_Start_IT(huart->hdmarx, (uint32_t)&huart->Instance->DR, *(uint32_t *)tmp, Size); + + /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ + __HAL_UART_CLEAR_OREFLAG(huart); + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + if (huart->Init.Parity != UART_PARITY_NONE) + { + /* Enable the UART Parity Error Interrupt */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); + } + + /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the UART CR3 register */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + return HAL_OK; +} + +/** + * @brief End ongoing Tx transfer on UART peripheral (following error detection or Transmit completion). + * @param huart UART handle. + * @retval None + */ +static void UART_EndTxTransfer(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* At end of Tx process, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; +} + +/** + * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion). + * @param huart UART handle. + * @retval None + */ +static void UART_EndRxTransfer(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* In case of reception waiting for IDLE event, disable also the IDLE IE interrupt source */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; +} + +/** + * @brief DMA UART communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + huart->RxXferCount = 0x00U; + huart->TxXferCount = 0x00U; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->hdmatx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (huart->hdmarx != NULL) + { + if (huart->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->hdmarx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (huart->hdmatx != NULL) + { + if (huart->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Tx communication abort callback, when initiated by user by a call to + * HAL_UART_AbortTransmit_IT API (Abort only Tx transfer) + * (This callback is executed at end of DMA Tx Abort procedure following user abort request, + * and leads to user Tx Abort Complete callback execution). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Rx communication abort callback, when initiated by user by a call to + * HAL_UART_AbortReceive_IT API (Abort only Rx transfer) + * (This callback is executed at end of DMA Rx Abort procedure following user abort request, + * and leads to user Rx Abort Complete callback execution). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief Sends an amount of data in non blocking mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart) +{ + const uint16_t *tmp; + + /* Check that a Tx process is ongoing */ + if (huart->gState == HAL_UART_STATE_BUSY_TX) + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + tmp = (const uint16_t *) huart->pTxBuffPtr; + huart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); + huart->pTxBuffPtr += 2U; + } + else + { + huart->Instance->DR = (uint8_t)(*huart->pTxBuffPtr++ & (uint8_t)0x00FF); + } + + if (--huart->TxXferCount == 0U) + { + /* Disable the UART Transmit Data Register Empty Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_TXE); + + /* Enable the UART Transmit Complete Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_TC); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Wraps up transmission in non blocking mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart) +{ + /* Disable the UART Transmit Complete Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_TC); + + /* Tx process is ended, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + + return HAL_OK; +} + +/** + * @brief Receives an amount of data in non blocking mode + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + + /* Check that a Rx process is ongoing */ + if (huart->RxState == HAL_UART_STATE_BUSY_RX) + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) huart->pRxBuffPtr; + *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); + huart->pRxBuffPtr += 2U; + } + else + { + pdata8bits = (uint8_t *) huart->pRxBuffPtr; + pdata16bits = NULL; + + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + huart->pRxBuffPtr += 1U; + } + + if (--huart->RxXferCount == 0U) + { + /* Disable the UART Data Register not empty Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_RXNE); + + /* Disable the UART Parity Error Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_PE); + + /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + __HAL_UART_DISABLE_IT(huart, UART_IT_ERR); + + /* Rx process is completed, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + /* Check current reception Mode : + If Reception till IDLE event has been selected : */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + /* Set reception type to Standard */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Disable IDLE interrupt */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + + /* Check if IDLE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) + { + /* Clear IDLE flag in ISR */ + __HAL_UART_CLEAR_IDLEFLAG(huart); + } + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* Standard reception API called */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxCpltCallback(huart); +#else + /*Call legacy weak Rx complete callback*/ + HAL_UART_RxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures the UART peripheral. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +static void UART_SetConfig(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg; + uint32_t pclk; + + /* Check the parameters */ + assert_param(IS_UART_BAUDRATE(huart->Init.BaudRate)); + assert_param(IS_UART_STOPBITS(huart->Init.StopBits)); + assert_param(IS_UART_PARITY(huart->Init.Parity)); + assert_param(IS_UART_MODE(huart->Init.Mode)); + + /*-------------------------- USART CR2 Configuration -----------------------*/ + /* Configure the UART Stop Bits: Set STOP[13:12] bits + according to huart->Init.StopBits value */ + MODIFY_REG(huart->Instance->CR2, USART_CR2_STOP, huart->Init.StopBits); + + /*-------------------------- USART CR1 Configuration -----------------------*/ + /* Configure the UART Word Length, Parity and mode: + Set the M bits according to huart->Init.WordLength value + Set PCE and PS bits according to huart->Init.Parity value + Set TE and RE bits according to huart->Init.Mode value + Set OVER8 bit according to huart->Init.OverSampling value */ + + tmpreg = (uint32_t)huart->Init.WordLength | huart->Init.Parity | huart->Init.Mode | huart->Init.OverSampling; + MODIFY_REG(huart->Instance->CR1, + (uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), + tmpreg); + + /*-------------------------- USART CR3 Configuration -----------------------*/ + /* Configure the UART HFC: Set CTSE and RTSE bits according to huart->Init.HwFlowCtl value */ + MODIFY_REG(huart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE), huart->Init.HwFlowCtl); + + +#if defined(USART6) && defined(UART9) && defined(UART10) + if ((huart->Instance == USART1) || (huart->Instance == USART6) || (huart->Instance == UART9) || (huart->Instance == UART10)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#elif defined(USART6) + if ((huart->Instance == USART1) || (huart->Instance == USART6)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#else + if (huart->Instance == USART1) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#endif /* USART6 */ + else + { + pclk = HAL_RCC_GetPCLK1Freq(); + } + /*-------------------------- USART BRR Configuration ---------------------*/ + if (huart->Init.OverSampling == UART_OVERSAMPLING_8) + { + huart->Instance->BRR = UART_BRR_SAMPLING8(pclk, huart->Init.BaudRate); + } + else + { + huart->Instance->BRR = UART_BRR_SAMPLING16(pclk, huart->Init.BaudRate); + } +} + +/** + * @} + */ + +#endif /* HAL_UART_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c new file mode 100644 index 0000000..76e14ae --- /dev/null +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c @@ -0,0 +1,922 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_adc.c + * @author MCD Application Team + * @brief ADC LL module driver + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_adc.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT + #include "stm32_assert.h" +#else + #define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (ADC1) || defined (ADC2) || defined (ADC3) + +/** @addtogroup ADC_LL ADC + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ + +/** @addtogroup ADC_LL_Private_Macros + * @{ + */ + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* common to several ADC instances. */ +#define IS_LL_ADC_COMMON_CLOCK(__CLOCK__) \ + ( ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV2) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV4) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV6) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV8) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC instance. */ +#define IS_LL_ADC_RESOLUTION(__RESOLUTION__) \ + ( ((__RESOLUTION__) == LL_ADC_RESOLUTION_12B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_10B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_8B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_6B) \ + ) + +#define IS_LL_ADC_DATA_ALIGN(__DATA_ALIGN__) \ + ( ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_RIGHT) \ + || ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_LEFT) \ + ) + +#define IS_LL_ADC_SCAN_SELECTION(__SCAN_SELECTION__) \ + ( ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_DISABLE) \ + || ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_ENABLE) \ + ) + +#define IS_LL_ADC_SEQ_SCAN_MODE(__SEQ_SCAN_MODE__) \ + ( ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_DISABLE) \ + || ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_ENABLE) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC group regular */ +#define IS_LL_ADC_REG_TRIG_SOURCE(__REG_TRIG_SOURCE__) \ + ( ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_SOFTWARE) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH4) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM4_CH4) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_EXTI_LINE11) \ + ) +#define IS_LL_ADC_REG_CONTINUOUS_MODE(__REG_CONTINUOUS_MODE__) \ + ( ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_SINGLE) \ + || ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_CONTINUOUS) \ + ) + +#define IS_LL_ADC_REG_DMA_TRANSFER(__REG_DMA_TRANSFER__) \ + ( ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_NONE) \ + || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_LIMITED) \ + || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_UNLIMITED) \ + ) + +#define IS_LL_ADC_REG_FLAG_EOC_SELECTION(__REG_FLAG_EOC_SELECTION__) \ + ( ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV) \ + || ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_UNITARY_CONV) \ + ) + +#define IS_LL_ADC_REG_SEQ_SCAN_LENGTH(__REG_SEQ_SCAN_LENGTH__) \ + ( ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_DISABLE) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS) \ + ) + +#define IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(__REG_SEQ_DISCONT_MODE__) \ + ( ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_DISABLE) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_1RANK) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_2RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_3RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_4RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_5RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_6RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_7RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_8RANKS) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC group injected */ +#define IS_LL_ADC_INJ_TRIG_SOURCE(__INJ_TRIG_SOURCE__) \ + ( ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_SOFTWARE) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_CH1) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH1) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH3) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH3) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_EXTI_LINE15) \ + ) + +#define IS_LL_ADC_INJ_TRIG_EXT_EDGE(__INJ_TRIG_EXT_EDGE__) \ + ( ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISING) \ + || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_FALLING) \ + || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISINGFALLING) \ + ) + +#define IS_LL_ADC_INJ_TRIG_AUTO(__INJ_TRIG_AUTO__) \ + ( ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_INDEPENDENT) \ + || ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_FROM_GRP_REGULAR) \ + ) + +#define IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(__INJ_SEQ_SCAN_LENGTH__) \ + ( ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_DISABLE) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS) \ + ) + +#define IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(__INJ_SEQ_DISCONT_MODE__) \ + ( ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_DISABLE) \ + || ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_1RANK) \ + ) + +#if defined(ADC_MULTIMODE_SUPPORT) +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* multimode. */ +#if defined(ADC3) +#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ + ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_ALTERN) \ + ) +#else +#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ + ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ + ) +#endif + +#define IS_LL_ADC_MULTI_DMA_TRANSFER(__MULTI_DMA_TRANSFER__) \ + ( ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_EACH_ADC) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_1) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_2) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_3) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_1) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_2) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_3) \ + ) + +#define IS_LL_ADC_MULTI_TWOSMP_DELAY(__MULTI_TWOSMP_DELAY__) \ + ( ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES) \ + ) + +#define IS_LL_ADC_MULTI_MASTER_SLAVE(__MULTI_MASTER_SLAVE__) \ + ( ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER) \ + || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_SLAVE) \ + || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER_SLAVE) \ + ) + +#endif /* ADC_MULTIMODE_SUPPORT */ +/** + * @} + */ + + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup ADC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup ADC_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize registers of all ADC instances belonging to + * the same ADC common instance to their default reset values. + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC common registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON) +{ + /* Check the parameters */ + assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); + + + /* Force reset of ADC clock (core clock) */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_ADC); + + /* Release reset of ADC clock (core clock) */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_ADC); + + return SUCCESS; +} + +/** + * @brief Initialize some features of ADC common parameters + * (all ADC instances belonging to the same ADC common instance) + * and multimode (for devices with several ADC instances available). + * @note The setting of ADC common parameters is conditioned to + * ADC instances state: + * All ADC instances belonging to the same ADC common instance + * must be disabled. + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC common registers are initialized + * - ERROR: ADC common registers are not initialized + */ +ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); + assert_param(IS_LL_ADC_COMMON_CLOCK(ADC_CommonInitStruct->CommonClock)); + +#if defined(ADC_MULTIMODE_SUPPORT) + assert_param(IS_LL_ADC_MULTI_MODE(ADC_CommonInitStruct->Multimode)); + if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) + { + assert_param(IS_LL_ADC_MULTI_DMA_TRANSFER(ADC_CommonInitStruct->MultiDMATransfer)); + assert_param(IS_LL_ADC_MULTI_TWOSMP_DELAY(ADC_CommonInitStruct->MultiTwoSamplingDelay)); + } +#endif /* ADC_MULTIMODE_SUPPORT */ + + /* Note: Hardware constraint (refer to description of functions */ + /* "LL_ADC_SetCommonXXX()" and "LL_ADC_SetMultiXXX()"): */ + /* On this STM32 series, setting of these features is conditioned to */ + /* ADC state: */ + /* All ADC instances of the ADC common group must be disabled. */ + if(__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(ADCxy_COMMON) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - common to several ADC */ + /* (all ADC instances belonging to the same ADC common instance) */ + /* - Set ADC clock (conversion clock) */ + /* - multimode (if several ADC instances available on the */ + /* selected device) */ + /* - Set ADC multimode configuration */ + /* - Set ADC multimode DMA transfer */ + /* - Set ADC multimode: delay between 2 sampling phases */ +#if defined(ADC_MULTIMODE_SUPPORT) + if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) + { + MODIFY_REG(ADCxy_COMMON->CCR, + ADC_CCR_ADCPRE + | ADC_CCR_MULTI + | ADC_CCR_DMA + | ADC_CCR_DDS + | ADC_CCR_DELAY + , + ADC_CommonInitStruct->CommonClock + | ADC_CommonInitStruct->Multimode + | ADC_CommonInitStruct->MultiDMATransfer + | ADC_CommonInitStruct->MultiTwoSamplingDelay + ); + } + else + { + MODIFY_REG(ADCxy_COMMON->CCR, + ADC_CCR_ADCPRE + | ADC_CCR_MULTI + | ADC_CCR_DMA + | ADC_CCR_DDS + | ADC_CCR_DELAY + , + ADC_CommonInitStruct->CommonClock + | LL_ADC_MULTI_INDEPENDENT + ); + } +#else + LL_ADC_SetCommonClock(ADCxy_COMMON, ADC_CommonInitStruct->CommonClock); +#endif + } + else + { + /* Initialization error: One or several ADC instances belonging to */ + /* the same ADC common instance are not disabled. */ + status = ERROR; + } + + return status; +} + +/** + * @brief Set each @ref LL_ADC_CommonInitTypeDef field to default value. + * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) +{ + /* Set ADC_CommonInitStruct fields to default values */ + /* Set fields of ADC common */ + /* (all ADC instances belonging to the same ADC common instance) */ + ADC_CommonInitStruct->CommonClock = LL_ADC_CLOCK_SYNC_PCLK_DIV2; + +#if defined(ADC_MULTIMODE_SUPPORT) + /* Set fields of ADC multimode */ + ADC_CommonInitStruct->Multimode = LL_ADC_MULTI_INDEPENDENT; + ADC_CommonInitStruct->MultiDMATransfer = LL_ADC_MULTI_REG_DMA_EACH_ADC; + ADC_CommonInitStruct->MultiTwoSamplingDelay = LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES; +#endif /* ADC_MULTIMODE_SUPPORT */ +} + +/** + * @brief De-initialize registers of the selected ADC instance + * to their default reset values. + * @note To reset all ADC instances quickly (perform a hard reset), + * use function @ref LL_ADC_CommonDeInit(). + * @param ADCx ADC instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are de-initialized + * - ERROR: ADC registers are not de-initialized + */ +ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + + /* Disable ADC instance if not already disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 1UL) + { + /* Set ADC group regular trigger source to SW start to ensure to not */ + /* have an external trigger event occurring during the conversion stop */ + /* ADC disable process. */ + LL_ADC_REG_SetTriggerSource(ADCx, LL_ADC_REG_TRIG_SOFTWARE); + + /* Set ADC group injected trigger source to SW start to ensure to not */ + /* have an external trigger event occurring during the conversion stop */ + /* ADC disable process. */ + LL_ADC_INJ_SetTriggerSource(ADCx, LL_ADC_INJ_TRIG_SOFTWARE); + + /* Disable the ADC instance */ + LL_ADC_Disable(ADCx); + } + + /* Check whether ADC state is compliant with expected state */ + /* (hardware requirements of bits state to reset registers below) */ + if(READ_BIT(ADCx->CR2, ADC_CR2_ADON) == 0UL) + { + /* ========== Reset ADC registers ========== */ + /* Reset register SR */ + CLEAR_BIT(ADCx->SR, + ( LL_ADC_FLAG_STRT + | LL_ADC_FLAG_JSTRT + | LL_ADC_FLAG_EOCS + | LL_ADC_FLAG_OVR + | LL_ADC_FLAG_JEOS + | LL_ADC_FLAG_AWD1 ) + ); + + /* Reset register CR1 */ + CLEAR_BIT(ADCx->CR1, + ( ADC_CR1_OVRIE | ADC_CR1_RES | ADC_CR1_AWDEN + | ADC_CR1_JAWDEN + | ADC_CR1_DISCNUM | ADC_CR1_JDISCEN | ADC_CR1_DISCEN + | ADC_CR1_JAUTO | ADC_CR1_AWDSGL | ADC_CR1_SCAN + | ADC_CR1_JEOCIE | ADC_CR1_AWDIE | ADC_CR1_EOCIE + | ADC_CR1_AWDCH ) + ); + + /* Reset register CR2 */ + CLEAR_BIT(ADCx->CR2, + ( ADC_CR2_SWSTART | ADC_CR2_EXTEN | ADC_CR2_EXTSEL + | ADC_CR2_JSWSTART | ADC_CR2_JEXTEN | ADC_CR2_JEXTSEL + | ADC_CR2_ALIGN | ADC_CR2_EOCS + | ADC_CR2_DDS | ADC_CR2_DMA + | ADC_CR2_CONT | ADC_CR2_ADON ) + ); + + /* Reset register SMPR1 */ + CLEAR_BIT(ADCx->SMPR1, + ( ADC_SMPR1_SMP18 | ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16 + | ADC_SMPR1_SMP15 | ADC_SMPR1_SMP14 | ADC_SMPR1_SMP13 + | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP10) + ); + + /* Reset register SMPR2 */ + CLEAR_BIT(ADCx->SMPR2, + ( ADC_SMPR2_SMP9 + | ADC_SMPR2_SMP8 | ADC_SMPR2_SMP7 | ADC_SMPR2_SMP6 + | ADC_SMPR2_SMP5 | ADC_SMPR2_SMP4 | ADC_SMPR2_SMP3 + | ADC_SMPR2_SMP2 | ADC_SMPR2_SMP1 | ADC_SMPR2_SMP0) + ); + + /* Reset register JOFR1 */ + CLEAR_BIT(ADCx->JOFR1, ADC_JOFR1_JOFFSET1); + /* Reset register JOFR2 */ + CLEAR_BIT(ADCx->JOFR2, ADC_JOFR2_JOFFSET2); + /* Reset register JOFR3 */ + CLEAR_BIT(ADCx->JOFR3, ADC_JOFR3_JOFFSET3); + /* Reset register JOFR4 */ + CLEAR_BIT(ADCx->JOFR4, ADC_JOFR4_JOFFSET4); + + /* Reset register HTR */ + SET_BIT(ADCx->HTR, ADC_HTR_HT); + /* Reset register LTR */ + CLEAR_BIT(ADCx->LTR, ADC_LTR_LT); + + /* Reset register SQR1 */ + CLEAR_BIT(ADCx->SQR1, + ( ADC_SQR1_L + | ADC_SQR1_SQ16 + | ADC_SQR1_SQ15 | ADC_SQR1_SQ14 | ADC_SQR1_SQ13) + ); + + /* Reset register SQR2 */ + CLEAR_BIT(ADCx->SQR2, + ( ADC_SQR2_SQ12 | ADC_SQR2_SQ11 | ADC_SQR2_SQ10 + | ADC_SQR2_SQ9 | ADC_SQR2_SQ8 | ADC_SQR2_SQ7) + ); + + /* Reset register SQR3 */ + CLEAR_BIT(ADCx->SQR3, + ( ADC_SQR3_SQ6 | ADC_SQR3_SQ5 | ADC_SQR3_SQ4 + | ADC_SQR3_SQ3 | ADC_SQR3_SQ2 | ADC_SQR3_SQ1) + ); + + /* Reset register JSQR */ + CLEAR_BIT(ADCx->JSQR, + ( ADC_JSQR_JL + | ADC_JSQR_JSQ4 | ADC_JSQR_JSQ3 + | ADC_JSQR_JSQ2 | ADC_JSQR_JSQ1 ) + ); + + /* Reset register DR */ + /* bits in access mode read only, no direct reset applicable */ + + /* Reset registers JDR1, JDR2, JDR3, JDR4 */ + /* bits in access mode read only, no direct reset applicable */ + + /* Reset register CCR */ + CLEAR_BIT(ADC->CCR, ADC_CCR_TSVREFE | ADC_CCR_ADCPRE); + } + + return status; +} + +/** + * @brief Initialize some features of ADC instance. + * @note These parameters have an impact on ADC scope: ADC instance. + * Affects both group regular and group injected (availability + * of ADC group injected depends on STM32 families). + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Instance . + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, some other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group regular or group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + + assert_param(IS_LL_ADC_RESOLUTION(ADC_InitStruct->Resolution)); + assert_param(IS_LL_ADC_DATA_ALIGN(ADC_InitStruct->DataAlignment)); + assert_param(IS_LL_ADC_SCAN_SELECTION(ADC_InitStruct->SequencersScanMode)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC instance */ + /* - Set ADC data resolution */ + /* - Set ADC conversion data alignment */ + MODIFY_REG(ADCx->CR1, + ADC_CR1_RES + | ADC_CR1_SCAN + , + ADC_InitStruct->Resolution + | ADC_InitStruct->SequencersScanMode + ); + + MODIFY_REG(ADCx->CR2, + ADC_CR2_ALIGN + , + ADC_InitStruct->DataAlignment + ); + + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_InitTypeDef field to default value. + * @param ADC_InitStruct Pointer to a @ref LL_ADC_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct) +{ + /* Set ADC_InitStruct fields to default values */ + /* Set fields of ADC instance */ + ADC_InitStruct->Resolution = LL_ADC_RESOLUTION_12B; + ADC_InitStruct->DataAlignment = LL_ADC_DATA_ALIGN_RIGHT; + + /* Enable scan mode to have a generic behavior with ADC of other */ + /* STM32 families, without this setting available: */ + /* ADC group regular sequencer and ADC group injected sequencer depend */ + /* only of their own configuration. */ + ADC_InitStruct->SequencersScanMode = LL_ADC_SEQ_SCAN_ENABLE; + +} + +/** + * @brief Initialize some features of ADC group regular. + * @note These parameters have an impact on ADC scope: ADC group regular. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "REG"). + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group regular or group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + assert_param(IS_LL_ADC_REG_TRIG_SOURCE(ADC_REG_InitStruct->TriggerSource)); + assert_param(IS_LL_ADC_REG_SEQ_SCAN_LENGTH(ADC_REG_InitStruct->SequencerLength)); + if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + assert_param(IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(ADC_REG_InitStruct->SequencerDiscont)); + } + assert_param(IS_LL_ADC_REG_CONTINUOUS_MODE(ADC_REG_InitStruct->ContinuousMode)); + assert_param(IS_LL_ADC_REG_DMA_TRANSFER(ADC_REG_InitStruct->DMATransfer)); + + /* ADC group regular continuous mode and discontinuous mode */ + /* can not be enabled simultenaeously */ + assert_param((ADC_REG_InitStruct->ContinuousMode == LL_ADC_REG_CONV_SINGLE) + || (ADC_REG_InitStruct->SequencerDiscont == LL_ADC_REG_SEQ_DISCONT_DISABLE)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC group regular */ + /* - Set ADC group regular trigger source */ + /* - Set ADC group regular sequencer length */ + /* - Set ADC group regular sequencer discontinuous mode */ + /* - Set ADC group regular continuous mode */ + /* - Set ADC group regular conversion data transfer: no transfer or */ + /* transfer by DMA, and DMA requests mode */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ + if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_DISCEN + | ADC_CR1_DISCNUM + , + ADC_REG_InitStruct->SequencerDiscont + ); + } + else + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_DISCEN + | ADC_CR1_DISCNUM + , + LL_ADC_REG_SEQ_DISCONT_DISABLE + ); + } + + MODIFY_REG(ADCx->CR2, + ADC_CR2_EXTSEL + | ADC_CR2_EXTEN + | ADC_CR2_CONT + | ADC_CR2_DMA + | ADC_CR2_DDS + , + (ADC_REG_InitStruct->TriggerSource & ADC_CR2_EXTSEL) + | ADC_REG_InitStruct->ContinuousMode + | ADC_REG_InitStruct->DMATransfer + ); + + /* Set ADC group regular sequencer length and scan direction */ + /* Note: Hardware constraint (refer to description of this function): */ + /* Note: If ADC instance feature scan mode is disabled */ + /* (refer to ADC instance initialization structure */ + /* parameter @ref SequencersScanMode */ + /* or function @ref LL_ADC_SetSequencersScanMode() ), */ + /* this parameter is discarded. */ + LL_ADC_REG_SetSequencerLength(ADCx, ADC_REG_InitStruct->SequencerLength); + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_REG_InitTypeDef field to default value. + * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) +{ + /* Set ADC_REG_InitStruct fields to default values */ + /* Set fields of ADC group regular */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ + ADC_REG_InitStruct->TriggerSource = LL_ADC_REG_TRIG_SOFTWARE; + ADC_REG_InitStruct->SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE; + ADC_REG_InitStruct->SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE; + ADC_REG_InitStruct->ContinuousMode = LL_ADC_REG_CONV_SINGLE; + ADC_REG_InitStruct->DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE; +} + +/** + * @brief Initialize some features of ADC group injected. + * @note These parameters have an impact on ADC scope: ADC group injected. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "INJ"). + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_INJ_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + assert_param(IS_LL_ADC_INJ_TRIG_SOURCE(ADC_INJ_InitStruct->TriggerSource)); + assert_param(IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(ADC_INJ_InitStruct->SequencerLength)); + if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_INJ_SEQ_SCAN_DISABLE) + { + assert_param(IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(ADC_INJ_InitStruct->SequencerDiscont)); + } + assert_param(IS_LL_ADC_INJ_TRIG_AUTO(ADC_INJ_InitStruct->TrigAuto)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC group injected */ + /* - Set ADC group injected trigger source */ + /* - Set ADC group injected sequencer length */ + /* - Set ADC group injected sequencer discontinuous mode */ + /* - Set ADC group injected conversion trigger: independent or */ + /* from ADC group regular */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_INJ_StartConversionExtTrig(). */ + if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_JDISCEN + | ADC_CR1_JAUTO + , + ADC_INJ_InitStruct->SequencerDiscont + | ADC_INJ_InitStruct->TrigAuto + ); + } + else + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_JDISCEN + | ADC_CR1_JAUTO + , + LL_ADC_REG_SEQ_DISCONT_DISABLE + | ADC_INJ_InitStruct->TrigAuto + ); + } + + MODIFY_REG(ADCx->CR2, + ADC_CR2_JEXTSEL + | ADC_CR2_JEXTEN + , + (ADC_INJ_InitStruct->TriggerSource & ADC_CR2_JEXTSEL) + ); + + /* Note: Hardware constraint (refer to description of this function): */ + /* Note: If ADC instance feature scan mode is disabled */ + /* (refer to ADC instance initialization structure */ + /* parameter @ref SequencersScanMode */ + /* or function @ref LL_ADC_SetSequencersScanMode() ), */ + /* this parameter is discarded. */ + LL_ADC_INJ_SetSequencerLength(ADCx, ADC_INJ_InitStruct->SequencerLength); + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_INJ_InitTypeDef field to default value. + * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) +{ + /* Set ADC_INJ_InitStruct fields to default values */ + /* Set fields of ADC group injected */ + ADC_INJ_InitStruct->TriggerSource = LL_ADC_INJ_TRIG_SOFTWARE; + ADC_INJ_InitStruct->SequencerLength = LL_ADC_INJ_SEQ_SCAN_DISABLE; + ADC_INJ_InitStruct->SequencerDiscont = LL_ADC_INJ_SEQ_DISCONT_DISABLE; + ADC_INJ_InitStruct->TrigAuto = LL_ADC_INJ_TRIG_INDEPENDENT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* ADC1 || ADC2 || ADC3 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + diff --git a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c index 1df5fcf..fbd4bc0 100644 --- a/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c +++ b/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c @@ -1,2224 +1,2224 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usb.c - * @author MCD Application Team - * @brief USB Low Layer HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Initialization/de-initialization functions - * + I/O operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - ****************************************************************************** - * @attention - * - * Copyright (c) 2016 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Fill parameters of Init structure in USB_OTG_CfgTypeDef structure. - - (#) Call USB_CoreInit() API to initialize the USB Core peripheral. - - (#) The upper HAL HCD/PCD driver will call the right routines for its internal processes. - - @endverbatim - - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_LL_USB_DRIVER - * @{ - */ - -#if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx); - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup USB_LL_Exported_Functions USB Low Layer Exported Functions - * @{ - */ - -/** @defgroup USB_LL_Exported_Functions_Group1 Initialization/de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization/de-initialization functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the USB Core - * @param USBx USB Instance - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - HAL_StatusTypeDef ret; - if (cfg.phy_itface == USB_OTG_ULPI_PHY) - { - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - - /* Init The ULPI Interface */ - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); - - /* Select vbus source */ - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - if (cfg.use_external_vbus == 1U) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_ULPIEVBUSD; - } - - /* Reset after a PHY select */ - ret = USB_CoreReset(USBx); - } - else /* FS interface (embedded Phy) */ - { - /* Select FS Embedded PHY */ - USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - - /* Reset after a PHY select */ - ret = USB_CoreReset(USBx); - - if (cfg.battery_charging_enable == 0U) - { - /* Activate the USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - else - { - /* Deactivate the USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - } - - if (cfg.dma_enable == 1U) - { - USBx->GAHBCFG |= USB_OTG_GAHBCFG_HBSTLEN_2; - USBx->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; - } - - return ret; -} - - -/** - * @brief Set the USB turnaround time - * @param USBx USB Instance - * @param hclk: AHB clock frequency - * @retval USB turnaround time In PHY Clocks number - */ -HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, - uint32_t hclk, uint8_t speed) -{ - uint32_t UsbTrd; - - /* The USBTRD is configured according to the tables below, depending on AHB frequency - used by application. In the low AHB frequency range it is used to stretch enough the USB response - time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access - latency to the Data FIFO */ - if (speed == USBD_FS_SPEED) - { - if ((hclk >= 14200000U) && (hclk < 15000000U)) - { - /* hclk Clock Range between 14.2-15 MHz */ - UsbTrd = 0xFU; - } - else if ((hclk >= 15000000U) && (hclk < 16000000U)) - { - /* hclk Clock Range between 15-16 MHz */ - UsbTrd = 0xEU; - } - else if ((hclk >= 16000000U) && (hclk < 17200000U)) - { - /* hclk Clock Range between 16-17.2 MHz */ - UsbTrd = 0xDU; - } - else if ((hclk >= 17200000U) && (hclk < 18500000U)) - { - /* hclk Clock Range between 17.2-18.5 MHz */ - UsbTrd = 0xCU; - } - else if ((hclk >= 18500000U) && (hclk < 20000000U)) - { - /* hclk Clock Range between 18.5-20 MHz */ - UsbTrd = 0xBU; - } - else if ((hclk >= 20000000U) && (hclk < 21800000U)) - { - /* hclk Clock Range between 20-21.8 MHz */ - UsbTrd = 0xAU; - } - else if ((hclk >= 21800000U) && (hclk < 24000000U)) - { - /* hclk Clock Range between 21.8-24 MHz */ - UsbTrd = 0x9U; - } - else if ((hclk >= 24000000U) && (hclk < 27700000U)) - { - /* hclk Clock Range between 24-27.7 MHz */ - UsbTrd = 0x8U; - } - else if ((hclk >= 27700000U) && (hclk < 32000000U)) - { - /* hclk Clock Range between 27.7-32 MHz */ - UsbTrd = 0x7U; - } - else /* if(hclk >= 32000000) */ - { - /* hclk Clock Range between 32-200 MHz */ - UsbTrd = 0x6U; - } - } - else if (speed == USBD_HS_SPEED) - { - UsbTrd = USBD_HS_TRDT_VALUE; - } - else - { - UsbTrd = USBD_DEFAULT_TRDT_VALUE; - } - - USBx->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - USBx->GUSBCFG |= (uint32_t)((UsbTrd << 10) & USB_OTG_GUSBCFG_TRDT); - - return HAL_OK; -} - -/** - * @brief USB_EnableGlobalInt - * Enables the controller's Global Int in the AHB Config reg - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx) -{ - USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; - return HAL_OK; -} - -/** - * @brief USB_DisableGlobalInt - * Disable the controller's Global Int in the AHB Config reg - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx) -{ - USBx->GAHBCFG &= ~USB_OTG_GAHBCFG_GINT; - return HAL_OK; -} - -/** - * @brief USB_SetCurrentMode Set functional mode - * @param USBx Selected device - * @param mode current core mode - * This parameter can be one of these values: - * @arg USB_DEVICE_MODE Peripheral mode - * @arg USB_HOST_MODE Host mode - * @retval HAL status - */ -HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode) -{ - uint32_t ms = 0U; - - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); - - if (mode == USB_HOST_MODE) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FHMOD; - - do - { - HAL_Delay(1U); - ms++; - } while ((USB_GetMode(USBx) != (uint32_t)USB_HOST_MODE) && (ms < 50U)); - } - else if (mode == USB_DEVICE_MODE) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - - do - { - HAL_Delay(1U); - ms++; - } while ((USB_GetMode(USBx) != (uint32_t)USB_DEVICE_MODE) && (ms < 50U)); - } - else - { - return HAL_ERROR; - } - - if (ms == 50U) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief USB_DevInit Initializes the USB_OTG controller registers - * for device mode - * @param USBx Selected device - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - for (i = 0U; i < 15U; i++) - { - USBx->DIEPTXF[i] = 0U; - } - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* VBUS Sensing setup */ - if (cfg.vbus_sensing_enable == 0U) - { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - - /* Deactivate VBUS Sensing B */ - USBx->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - /* B-peripheral session valid override enable */ - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - } - else - { - /* Enable HW VBUS sensing */ - USBx->GCCFG |= USB_OTG_GCCFG_VBDEN; - } -#else - /* VBUS Sensing setup */ - if (cfg.vbus_sensing_enable == 0U) - { - /* - * Disable HW VBUS sensing. VBUS is internally considered to be always - * at VBUS-Valid level (5V). - */ - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; - } - else - { - /* Enable HW VBUS sensing */ - USBx->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - - /* Restart the Phy Clock */ - USBx_PCGCCTL = 0U; - - /* Device mode configuration */ - USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; - - if (cfg.phy_itface == USB_OTG_ULPI_PHY) - { - if (cfg.speed == USBD_HS_SPEED) - { - /* Set Core speed to High speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH); - } - else - { - /* Set Core speed to Full speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH_IN_FULL); - } - } - else - { - /* Set Core speed to Full speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_FULL); - } - - /* Flush the FIFOs */ - if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ - { - ret = HAL_ERROR; - } - - if (USB_FlushRxFifo(USBx) != HAL_OK) - { - ret = HAL_ERROR; - } - - /* Clear all pending Device Interrupts */ - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - - for (i = 0U; i < cfg.dev_endpoints; i++) - { - if ((USBx_INEP(i)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - if (i == 0U) - { - USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_SNAK; - } - else - { - USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_EPDIS | USB_OTG_DIEPCTL_SNAK; - } - } - else - { - USBx_INEP(i)->DIEPCTL = 0U; - } - - USBx_INEP(i)->DIEPTSIZ = 0U; - USBx_INEP(i)->DIEPINT = 0xFB7FU; - } - - for (i = 0U; i < cfg.dev_endpoints; i++) - { - if ((USBx_OUTEP(i)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - if (i == 0U) - { - USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_SNAK; - } - else - { - USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_EPDIS | USB_OTG_DOEPCTL_SNAK; - } - } - else - { - USBx_OUTEP(i)->DOEPCTL = 0U; - } - - USBx_OUTEP(i)->DOEPTSIZ = 0U; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - } - - USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); - - /* Disable all interrupts. */ - USBx->GINTMSK = 0U; - - /* Clear any pending interrupts */ - USBx->GINTSTS = 0xBFFFFFFFU; - - /* Enable the common interrupts */ - if (cfg.dma_enable == 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; - } - - /* Enable interrupts matching to the Device mode ONLY */ - USBx->GINTMSK |= USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_USBRST | - USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_IEPINT | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IISOIXFRM | - USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM; - - if (cfg.Sof_enable != 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_SOFM; - } - - if (cfg.vbus_sensing_enable == 1U) - { - USBx->GINTMSK |= (USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_OTGINT); - } - - return ret; -} - -/** - * @brief USB_FlushTxFifo Flush a Tx FIFO - * @param USBx Selected device - * @param num FIFO number - * This parameter can be a value from 1 to 15 - 15 means Flush all Tx FIFOs - * @retval HAL status - */ -HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num) -{ - __IO uint32_t count = 0U; - - /* Wait for AHB master IDLE state. */ - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); - - /* Flush TX Fifo */ - count = 0U; - USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (num << 6)); - - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); - - return HAL_OK; -} - -/** - * @brief USB_FlushRxFifo Flush Rx FIFO - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx) -{ - __IO uint32_t count = 0U; - - /* Wait for AHB master IDLE state. */ - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); - - /* Flush RX Fifo */ - count = 0U; - USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; - - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); - - return HAL_OK; -} - -/** - * @brief USB_SetDevSpeed Initializes the DevSpd field of DCFG register - * depending the PHY type and the enumeration speed of the device. - * @param USBx Selected device - * @param speed device speed - * This parameter can be one of these values: - * @arg USB_OTG_SPEED_HIGH: High speed mode - * @arg USB_OTG_SPEED_HIGH_IN_FULL: High speed core in Full Speed mode - * @arg USB_OTG_SPEED_FULL: Full speed mode - * @retval Hal status - */ -HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_DEVICE->DCFG |= speed; - return HAL_OK; -} - -/** - * @brief USB_GetDevSpeed Return the Dev Speed - * @param USBx Selected device - * @retval speed device speed - * This parameter can be one of these values: - * @arg USBD_HS_SPEED: High speed mode - * @arg USBD_FS_SPEED: Full speed mode - */ -uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t speed; - uint32_t DevEnumSpeed = USBx_DEVICE->DSTS & USB_OTG_DSTS_ENUMSPD; - - if (DevEnumSpeed == DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ) - { - speed = USBD_HS_SPEED; - } - else if ((DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ) || - (DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_48MHZ)) - { - speed = USBD_FS_SPEED; - } - else - { - speed = 0xFU; - } - - return speed; -} - -/** - * @brief Activate and configure an endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); - - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_USBAEP) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_USBAEP; - } - } - else - { - USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); - - if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DOEPCTL_USBAEP; - } - } - return HAL_OK; -} - -/** - * @brief Activate and configure a dedicated endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if (((USBx_INEP(epnum)->DIEPCTL) & USB_OTG_DIEPCTL_USBAEP) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_USBAEP; - } - - USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); - } - else - { - if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DOEPCTL_USBAEP; - } - - USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); - } - - return HAL_OK; -} - -/** - * @brief De-activate and de-initialize an endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; - } - - USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_USBAEP | - USB_OTG_DIEPCTL_MPSIZ | - USB_OTG_DIEPCTL_TXFNUM | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_EPTYP); - } - else - { - if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; - } - - USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_USBAEP | - USB_OTG_DOEPCTL_MPSIZ | - USB_OTG_DOEPCTL_SD0PID_SEVNFRM | - USB_OTG_DOEPCTL_EPTYP); - } - - return HAL_OK; -} - -/** - * @brief De-activate and de-initialize a dedicated endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; - } - - USBx_INEP(epnum)->DIEPCTL &= ~ USB_OTG_DIEPCTL_USBAEP; - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - } - else - { - if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; - } - - USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_USBAEP; - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - } - - return HAL_OK; -} - -/** - * @brief USB_EPStartXfer : setup and starts a transfer over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - uint16_t pktcnt; - - /* IN endpoint */ - if (ep->is_in == 1U) - { - /* Zero Length Packet? */ - if (ep->xfer_len == 0U) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - } - else - { - /* Program the transfer size and packet count - * as follows: xfersize = N * maxpacket + - * short_packet pktcnt = N + (short_packet - * exist ? 1 : 0) - */ - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & - (((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket) << 19)); - - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); - - if (ep->type == EP_TYPE_ISOC) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_MULCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_MULCNT & (1U << 29)); - } - } - - if (dma == 1U) - { - if ((uint32_t)ep->dma_addr != 0U) - { - USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); - } - - if (ep->type == EP_TYPE_ISOC) - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; - } - else - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; - } - } - - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - } - else - { - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - - if (ep->type != EP_TYPE_ISOC) - { - /* Enable the Tx FIFO Empty Interrupt for this EP */ - if (ep->xfer_len > 0U) - { - USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); - } - } - else - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; - } - else - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; - } - - (void)USB_WritePacket(USBx, ep->xfer_buff, ep->num, (uint16_t)ep->xfer_len, dma); - } - } - } - else /* OUT endpoint */ - { - /* Program the transfer size and packet count as follows: - * pktcnt = N - * xfersize = N * maxpacket - */ - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); - - if (ep->xfer_len == 0U) - { - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->maxpacket); - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - } - else - { - pktcnt = (uint16_t)((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket); - ep->xfer_size = ep->maxpacket * pktcnt; - - USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_PKTCNT & ((uint32_t)pktcnt << 19); - USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_XFRSIZ & ep->xfer_size; - } - - if (dma == 1U) - { - if ((uint32_t)ep->xfer_buff != 0U) - { - USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); - } - } - - if (ep->type == EP_TYPE_ISOC) - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SODDFRM; - } - else - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; - } - } - /* EP enable */ - USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); - } - - return HAL_OK; -} - -/** - * @brief USB_EP0StartXfer : setup and starts a transfer over the EP 0 - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* IN endpoint */ - if (ep->is_in == 1U) - { - /* Zero Length Packet? */ - if (ep->xfer_len == 0U) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - } - else - { - /* Program the transfer size and packet count - * as follows: xfersize = N * maxpacket + - * short_packet pktcnt = N + (short_packet - * exist ? 1 : 0) - */ - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - - if (ep->xfer_len > ep->maxpacket) - { - ep->xfer_len = ep->maxpacket; - } - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); - } - - if (dma == 1U) - { - if ((uint32_t)ep->dma_addr != 0U) - { - USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); - } - - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - } - else - { - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - - /* Enable the Tx FIFO Empty Interrupt for this EP */ - if (ep->xfer_len > 0U) - { - USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); - } - } - } - else /* OUT endpoint */ - { - /* Program the transfer size and packet count as follows: - * pktcnt = N - * xfersize = N * maxpacket - */ - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); - - if (ep->xfer_len > 0U) - { - ep->xfer_len = ep->maxpacket; - } - - /* Store transfer size, for EP0 this is equal to endpoint max packet size */ - ep->xfer_size = ep->maxpacket; - - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->xfer_size); - - if (dma == 1U) - { - if ((uint32_t)ep->xfer_buff != 0U) - { - USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); - } - } - - /* EP enable */ - USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); - } - - return HAL_OK; -} - - -/** - * @brief USB_EPStoptXfer Stop transfer on an EP - * @param USBx usb device instance - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPStopXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - - /* IN endpoint */ - if (ep->is_in == 1U) - { - /* EP enable, IN data in FIFO */ - if (((USBx_INEP(ep->num)->DIEPCTL) & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - USBx_INEP(ep->num)->DIEPCTL |= (USB_OTG_DIEPCTL_SNAK); - USBx_INEP(ep->num)->DIEPCTL |= (USB_OTG_DIEPCTL_EPDIS); - - do - { - count++; - - if (count > 10000U) - { - ret = HAL_ERROR; - break; - } - } while (((USBx_INEP(ep->num)->DIEPCTL) & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA); - } - } - else /* OUT endpoint */ - { - if (((USBx_OUTEP(ep->num)->DOEPCTL) & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - USBx_OUTEP(ep->num)->DOEPCTL |= (USB_OTG_DOEPCTL_SNAK); - USBx_OUTEP(ep->num)->DOEPCTL |= (USB_OTG_DOEPCTL_EPDIS); - - do - { - count++; - - if (count > 10000U) - { - ret = HAL_ERROR; - break; - } - } while (((USBx_OUTEP(ep->num)->DOEPCTL) & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA); - } - } - - return ret; -} - - -/** - * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated - * with the EP/channel - * @param USBx Selected device - * @param src pointer to source buffer - * @param ch_ep_num endpoint or host channel number - * @param len Number of bytes to write - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, - uint8_t ch_ep_num, uint16_t len, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t *pSrc = src; - uint32_t count32b; - uint32_t i; - - if (dma == 0U) - { - count32b = ((uint32_t)len + 3U) / 4U; - for (i = 0U; i < count32b; i++) - { - USBx_DFIFO((uint32_t)ch_ep_num) = __UNALIGNED_UINT32_READ(pSrc); - pSrc++; - pSrc++; - pSrc++; - pSrc++; - } - } - - return HAL_OK; -} - -/** - * @brief USB_ReadPacket : read a packet from the RX FIFO - * @param USBx Selected device - * @param dest source pointer - * @param len Number of bytes to read - * @retval pointer to destination buffer - */ -void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t *pDest = dest; - uint32_t pData; - uint32_t i; - uint32_t count32b = (uint32_t)len >> 2U; - uint16_t remaining_bytes = len % 4U; - - for (i = 0U; i < count32b; i++) - { - __UNALIGNED_UINT32_WRITE(pDest, USBx_DFIFO(0U)); - pDest++; - pDest++; - pDest++; - pDest++; - } - - /* When Number of data is not word aligned, read the remaining byte */ - if (remaining_bytes != 0U) - { - i = 0U; - __UNALIGNED_UINT32_WRITE(&pData, USBx_DFIFO(0U)); - - do - { - *(uint8_t *)pDest = (uint8_t)(pData >> (8U * (uint8_t)(i))); - i++; - pDest++; - remaining_bytes--; - } while (remaining_bytes != 0U); - } - - return ((void *)pDest); -} - -/** - * @brief USB_EPSetStall : set a stall condition over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - if (((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == 0U) && (epnum != 0U)) - { - USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_EPDIS); - } - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_STALL; - } - else - { - if (((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == 0U) && (epnum != 0U)) - { - USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_EPDIS); - } - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_STALL; - } - - return HAL_OK; -} - -/** - * @brief USB_EPClearStall : Clear a stall condition over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - USBx_INEP(epnum)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; /* DATA0 */ - } - } - else - { - USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; /* DATA0 */ - } - } - return HAL_OK; -} - -/** - * @brief USB_StopDevice : Stop the usb device mode - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx) -{ - HAL_StatusTypeDef ret; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - /* Clear Pending interrupt */ - for (i = 0U; i < 15U; i++) - { - USBx_INEP(i)->DIEPINT = 0xFB7FU; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - } - - /* Clear interrupt masks */ - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - - /* Flush the FIFO */ - ret = USB_FlushRxFifo(USBx); - if (ret != HAL_OK) - { - return ret; - } - - ret = USB_FlushTxFifo(USBx, 0x10U); - if (ret != HAL_OK) - { - return ret; - } - - return ret; -} - -/** - * @brief USB_SetDevAddress : Stop the usb device mode - * @param USBx Selected device - * @param address new device address to be assigned - * This parameter can be a value from 0 to 255 - * @retval HAL status - */ -HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_DEVICE->DCFG &= ~(USB_OTG_DCFG_DAD); - USBx_DEVICE->DCFG |= ((uint32_t)address << 4) & USB_OTG_DCFG_DAD; - - return HAL_OK; -} - -/** - * @brief USB_DevConnect : Connect the USB device by enabling Rpu - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* In case phy is stopped, ensure to ungate and restore the phy CLK */ - USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); - - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; - - return HAL_OK; -} - -/** - * @brief USB_DevDisconnect : Disconnect the USB device by disabling Rpu - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* In case phy is stopped, ensure to ungate and restore the phy CLK */ - USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); - - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - - return HAL_OK; -} - -/** - * @brief USB_ReadInterrupts: return the global USB interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t tmpreg; - - tmpreg = USBx->GINTSTS; - tmpreg &= USBx->GINTMSK; - - return tmpreg; -} - -/** - * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_DEVICE->DAINT; - tmpreg &= USBx_DEVICE->DAINTMSK; - - return ((tmpreg & 0xffff0000U) >> 16); -} - -/** - * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_DEVICE->DAINT; - tmpreg &= USBx_DEVICE->DAINTMSK; - - return ((tmpreg & 0xFFFFU)); -} - -/** - * @brief Returns Device OUT EP Interrupt register - * @param USBx Selected device - * @param epnum endpoint number - * This parameter can be a value from 0 to 15 - * @retval Device OUT EP Interrupt register - */ -uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_OUTEP((uint32_t)epnum)->DOEPINT; - tmpreg &= USBx_DEVICE->DOEPMSK; - - return tmpreg; -} - -/** - * @brief Returns Device IN EP Interrupt register - * @param USBx Selected device - * @param epnum endpoint number - * This parameter can be a value from 0 to 15 - * @retval Device IN EP Interrupt register - */ -uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - uint32_t msk; - uint32_t emp; - - msk = USBx_DEVICE->DIEPMSK; - emp = USBx_DEVICE->DIEPEMPMSK; - msk |= ((emp >> (epnum & EP_ADDR_MSK)) & 0x1U) << 7; - tmpreg = USBx_INEP((uint32_t)epnum)->DIEPINT & msk; - - return tmpreg; -} - -/** - * @brief USB_ClearInterrupts: clear a USB interrupt - * @param USBx Selected device - * @param interrupt flag - * @retval None - */ -void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt) -{ - USBx->GINTSTS |= interrupt; -} - -/** - * @brief Returns USB core mode - * @param USBx Selected device - * @retval return core mode : Host or Device - * This parameter can be one of these values: - * 0 : Host - * 1 : Device - */ -uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx) -{ - return ((USBx->GINTSTS) & 0x1U); -} - -/** - * @brief Activate EP0 for Setup transactions - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* Set the MPS of the IN EP0 to 64 bytes */ - USBx_INEP(0U)->DIEPCTL &= ~USB_OTG_DIEPCTL_MPSIZ; - - USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; - - return HAL_OK; -} - -/** - * @brief Prepare the EP0 to start the first control setup - * @param USBx Selected device - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @param psetup pointer to setup packet - * @retval HAL status - */ -HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - - if (gSNPSiD > USB_OTG_CORE_ID_300A) - { - if ((USBx_OUTEP(0U)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - return HAL_OK; - } - } - - USBx_OUTEP(0U)->DOEPTSIZ = 0U; - USBx_OUTEP(0U)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - USBx_OUTEP(0U)->DOEPTSIZ |= (3U * 8U); - USBx_OUTEP(0U)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_STUPCNT; - - if (dma == 1U) - { - USBx_OUTEP(0U)->DOEPDMA = (uint32_t)psetup; - /* EP enable */ - USBx_OUTEP(0U)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_USBAEP; - } - - return HAL_OK; -} - -/** - * @brief Reset the USB Core (needed after USB clock settings change) - * @param USBx Selected device - * @retval HAL status - */ -static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx) -{ - __IO uint32_t count = 0U; - - /* Wait for AHB master IDLE state. */ - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); - - /* Core Soft Reset */ - count = 0U; - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - - do - { - count++; - - if (count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - - return HAL_OK; -} - -/** - * @brief USB_HostInit : Initializes the USB OTG controller registers - * for Host mode - * @param USBx Selected device - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - /* Restart the Phy Clock */ - USBx_PCGCCTL = 0U; - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Disable HW VBUS sensing */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); -#else - /* - * Disable HW VBUS sensing. VBUS is internally considered to be always - * at VBUS-Valid level (5V). - */ - USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Disable Battery chargin detector */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - - if ((USBx->CID & (0x1U << 8)) != 0U) - { - if (cfg.speed == USBH_FSLS_SPEED) - { - /* Force Device Enumeration to FS/LS mode only */ - USBx_HOST->HCFG |= USB_OTG_HCFG_FSLSS; - } - else - { - /* Set default Max speed support */ - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); - } - } - else - { - /* Set default Max speed support */ - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); - } - - /* Make sure the FIFOs are flushed. */ - if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ - { - ret = HAL_ERROR; - } - - if (USB_FlushRxFifo(USBx) != HAL_OK) - { - ret = HAL_ERROR; - } - - /* Clear all pending HC Interrupts */ - for (i = 0U; i < cfg.Host_channels; i++) - { - USBx_HC(i)->HCINT = 0xFFFFFFFFU; - USBx_HC(i)->HCINTMSK = 0U; - } - - /* Disable all interrupts. */ - USBx->GINTMSK = 0U; - - /* Clear any pending interrupts */ - USBx->GINTSTS = 0xFFFFFFFFU; - - if ((USBx->CID & (0x1U << 8)) != 0U) - { - /* set Rx FIFO size */ - USBx->GRXFSIZ = 0x200U; - USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x100U << 16) & USB_OTG_NPTXFD) | 0x200U); - USBx->HPTXFSIZ = (uint32_t)(((0xE0U << 16) & USB_OTG_HPTXFSIZ_PTXFD) | 0x300U); - } - else - { - /* set Rx FIFO size */ - USBx->GRXFSIZ = 0x80U; - USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x60U << 16) & USB_OTG_NPTXFD) | 0x80U); - USBx->HPTXFSIZ = (uint32_t)(((0x40U << 16)& USB_OTG_HPTXFSIZ_PTXFD) | 0xE0U); - } - - /* Enable the common interrupts */ - if (cfg.dma_enable == 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; - } - - /* Enable interrupts matching to the Host mode ONLY */ - USBx->GINTMSK |= (USB_OTG_GINTMSK_PRTIM | USB_OTG_GINTMSK_HCIM | \ - USB_OTG_GINTMSK_SOFM | USB_OTG_GINTSTS_DISCINT | \ - USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM); - - return ret; -} - -/** - * @brief USB_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the - * HCFG register on the PHY type and set the right frame interval - * @param USBx Selected device - * @param freq clock frequency - * This parameter can be one of these values: - * HCFG_48_MHZ : Full Speed 48 MHz Clock - * HCFG_6_MHZ : Low Speed 6 MHz Clock - * @retval HAL status - */ -HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSPCS); - USBx_HOST->HCFG |= (uint32_t)freq & USB_OTG_HCFG_FSLSPCS; - - if (freq == HCFG_48_MHZ) - { - USBx_HOST->HFIR = 48000U; - } - else if (freq == HCFG_6_MHZ) - { - USBx_HOST->HFIR = 6000U; - } - else - { - /* ... */ - } - - return HAL_OK; -} - -/** - * @brief USB_OTG_ResetPort : Reset Host Port - * @param USBx Selected device - * @retval HAL status - * @note (1)The application must wait at least 10 ms - * before clearing the reset bit. - */ -HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - - hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | - USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); - - USBx_HPRT0 = (USB_OTG_HPRT_PRST | hprt0); - HAL_Delay(100U); /* See Note #1 */ - USBx_HPRT0 = ((~USB_OTG_HPRT_PRST) & hprt0); - HAL_Delay(10U); - - return HAL_OK; -} - -/** - * @brief USB_DriveVbus : activate or de-activate vbus - * @param state VBUS state - * This parameter can be one of these values: - * 0 : Deactivate VBUS - * 1 : Activate VBUS - * @retval HAL status - */ -HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - - hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | - USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); - - if (((hprt0 & USB_OTG_HPRT_PPWR) == 0U) && (state == 1U)) - { - USBx_HPRT0 = (USB_OTG_HPRT_PPWR | hprt0); - } - if (((hprt0 & USB_OTG_HPRT_PPWR) == USB_OTG_HPRT_PPWR) && (state == 0U)) - { - USBx_HPRT0 = ((~USB_OTG_HPRT_PPWR) & hprt0); - } - return HAL_OK; -} - -/** - * @brief Return Host Core speed - * @param USBx Selected device - * @retval speed : Host speed - * This parameter can be one of these values: - * @arg HCD_SPEED_HIGH: High speed mode - * @arg HCD_SPEED_FULL: Full speed mode - * @arg HCD_SPEED_LOW: Low speed mode - */ -uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - return ((hprt0 & USB_OTG_HPRT_PSPD) >> 17); -} - -/** - * @brief Return Host Current Frame number - * @param USBx Selected device - * @retval current frame number - */ -uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - return (USBx_HOST->HFNUM & USB_OTG_HFNUM_FRNUM); -} - -/** - * @brief Initialize a host channel - * @param USBx Selected device - * @param ch_num Channel number - * This parameter can be a value from 1 to 15 - * @param epnum Endpoint number - * This parameter can be a value from 1 to 15 - * @param dev_address Current device address - * This parameter can be a value from 0 to 255 - * @param speed Current device speed - * This parameter can be one of these values: - * @arg USB_OTG_SPEED_HIGH: High speed mode - * @arg USB_OTG_SPEED_FULL: Full speed mode - * @arg USB_OTG_SPEED_LOW: Low speed mode - * @param ep_type Endpoint Type - * This parameter can be one of these values: - * @arg EP_TYPE_CTRL: Control type - * @arg EP_TYPE_ISOC: Isochronous type - * @arg EP_TYPE_BULK: Bulk type - * @arg EP_TYPE_INTR: Interrupt type - * @param mps Max Packet Size - * This parameter can be a value from 0 to 32K - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, uint8_t speed, - uint8_t ep_type, uint16_t mps) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t HCcharEpDir; - uint32_t HCcharLowSpeed; - uint32_t HostCoreSpeed; - - /* Clear old interrupt conditions for this host channel. */ - USBx_HC((uint32_t)ch_num)->HCINT = 0xFFFFFFFFU; - - /* Enable channel interrupts required for this transfer. */ - switch (ep_type) - { - case EP_TYPE_CTRL: - case EP_TYPE_BULK: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_STALLM | - USB_OTG_HCINTMSK_TXERRM | - USB_OTG_HCINTMSK_DTERRM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_NAKM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; - } - else - { - if ((USBx->CID & (0x1U << 8)) != 0U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_NYET | - USB_OTG_HCINTMSK_ACKM; - } - } - break; - - case EP_TYPE_INTR: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_STALLM | - USB_OTG_HCINTMSK_TXERRM | - USB_OTG_HCINTMSK_DTERRM | - USB_OTG_HCINTMSK_NAKM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_FRMORM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; - } - - break; - - case EP_TYPE_ISOC: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_ACKM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_FRMORM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_TXERRM | USB_OTG_HCINTMSK_BBERRM); - } - break; - - default: - ret = HAL_ERROR; - break; - } - - /* Enable host channel Halt interrupt */ - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_CHHM; - - /* Enable the top level host channel interrupt. */ - USBx_HOST->HAINTMSK |= 1UL << (ch_num & 0xFU); - - /* Make sure host channel interrupts are enabled. */ - USBx->GINTMSK |= USB_OTG_GINTMSK_HCIM; - - /* Program the HCCHAR register */ - if ((epnum & 0x80U) == 0x80U) - { - HCcharEpDir = (0x1U << 15) & USB_OTG_HCCHAR_EPDIR; - } - else - { - HCcharEpDir = 0U; - } - - HostCoreSpeed = USB_GetHostSpeed(USBx); - - /* LS device plugged to HUB */ - if ((speed == HPRT0_PRTSPD_LOW_SPEED) && (HostCoreSpeed != HPRT0_PRTSPD_LOW_SPEED)) - { - HCcharLowSpeed = (0x1U << 17) & USB_OTG_HCCHAR_LSDEV; - } - else - { - HCcharLowSpeed = 0U; - } - - USBx_HC((uint32_t)ch_num)->HCCHAR = (((uint32_t)dev_address << 22) & USB_OTG_HCCHAR_DAD) | - ((((uint32_t)epnum & 0x7FU) << 11) & USB_OTG_HCCHAR_EPNUM) | - (((uint32_t)ep_type << 18) & USB_OTG_HCCHAR_EPTYP) | - ((uint32_t)mps & USB_OTG_HCCHAR_MPSIZ) | HCcharEpDir | HCcharLowSpeed; - - if ((ep_type == EP_TYPE_INTR) || (ep_type == EP_TYPE_ISOC)) - { - USBx_HC((uint32_t)ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM; - } - - return ret; -} - -/** - * @brief Start a transfer over a host channel - * @param USBx Selected device - * @param hc pointer to host channel structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t ch_num = (uint32_t)hc->ch_num; - __IO uint32_t tmpreg; - uint8_t is_oddframe; - uint16_t len_words; - uint16_t num_packets; - uint16_t max_hc_pkt_count = 256U; - - if (((USBx->CID & (0x1U << 8)) != 0U) && (hc->speed == USBH_HS_SPEED)) - { - /* in DMA mode host Core automatically issues ping in case of NYET/NAK */ - if ((dma == 1U) && ((hc->ep_type == EP_TYPE_CTRL) || (hc->ep_type == EP_TYPE_BULK))) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK &= ~(USB_OTG_HCINTMSK_NYET | - USB_OTG_HCINTMSK_ACKM | - USB_OTG_HCINTMSK_NAKM); - } - - if ((dma == 0U) && (hc->do_ping == 1U)) - { - (void)USB_DoPing(USBx, hc->ch_num); - return HAL_OK; - } - - } - - /* Compute the expected number of packets associated to the transfer */ - if (hc->xfer_len > 0U) - { - num_packets = (uint16_t)((hc->xfer_len + hc->max_packet - 1U) / hc->max_packet); - - if (num_packets > max_hc_pkt_count) - { - num_packets = max_hc_pkt_count; - hc->XferSize = (uint32_t)num_packets * hc->max_packet; - } - } - else - { - num_packets = 1U; - } - - /* - * For IN channel HCTSIZ.XferSize is expected to be an integer multiple of - * max_packet size. - */ - if (hc->ep_is_in != 0U) - { - hc->XferSize = (uint32_t)num_packets * hc->max_packet; - } - else - { - hc->XferSize = hc->xfer_len; - } - - /* Initialize the HCTSIZn register */ - USBx_HC(ch_num)->HCTSIZ = (hc->XferSize & USB_OTG_HCTSIZ_XFRSIZ) | - (((uint32_t)num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | - (((uint32_t)hc->data_pid << 29) & USB_OTG_HCTSIZ_DPID); - - if (dma != 0U) - { - /* xfer_buff MUST be 32-bits aligned */ - USBx_HC(ch_num)->HCDMA = (uint32_t)hc->xfer_buff; - } - - is_oddframe = (((uint32_t)USBx_HOST->HFNUM & 0x01U) != 0U) ? 0U : 1U; - USBx_HC(ch_num)->HCCHAR &= ~USB_OTG_HCCHAR_ODDFRM; - USBx_HC(ch_num)->HCCHAR |= (uint32_t)is_oddframe << 29; - - /* Set host channel enable */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - - /* make sure to set the correct ep direction */ - if (hc->ep_is_in != 0U) - { - tmpreg |= USB_OTG_HCCHAR_EPDIR; - } - else - { - tmpreg &= ~USB_OTG_HCCHAR_EPDIR; - } - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - - if (dma != 0U) /* dma mode */ - { - return HAL_OK; - } - - if ((hc->ep_is_in == 0U) && (hc->xfer_len > 0U)) - { - switch (hc->ep_type) - { - /* Non periodic transfer */ - case EP_TYPE_CTRL: - case EP_TYPE_BULK: - - len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); - - /* check if there is enough space in FIFO space */ - if (len_words > (USBx->HNPTXSTS & 0xFFFFU)) - { - /* need to process data in nptxfempty interrupt */ - USBx->GINTMSK |= USB_OTG_GINTMSK_NPTXFEM; - } - break; - - /* Periodic transfer */ - case EP_TYPE_INTR: - case EP_TYPE_ISOC: - len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); - /* check if there is enough space in FIFO space */ - if (len_words > (USBx_HOST->HPTXSTS & 0xFFFFU)) /* split the transfer */ - { - /* need to process data in ptxfempty interrupt */ - USBx->GINTMSK |= USB_OTG_GINTMSK_PTXFEM; - } - break; - - default: - break; - } - - /* Write packet into the Tx FIFO. */ - (void)USB_WritePacket(USBx, hc->xfer_buff, hc->ch_num, (uint16_t)hc->xfer_len, 0); - } - - return HAL_OK; -} - -/** - * @brief Read all host channel interrupts status - * @param USBx Selected device - * @retval HAL state - */ -uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - return ((USBx_HOST->HAINT) & 0xFFFFU); -} - -/** - * @brief Halt a host channel - * @param USBx Selected device - * @param hc_num Host Channel number - * This parameter can be a value from 1 to 15 - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t hcnum = (uint32_t)hc_num; - __IO uint32_t count = 0U; - uint32_t HcEpType = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_EPTYP) >> 18; - uint32_t ChannelEna = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) >> 31; - - if (((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == USB_OTG_GAHBCFG_DMAEN) && - (ChannelEna == 0U)) - { - return HAL_OK; - } - - /* Check for space in the request queue to issue the halt. */ - if ((HcEpType == HCCHAR_CTRL) || (HcEpType == HCCHAR_BULK)) - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; - - if ((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == 0U) - { - if ((USBx->HNPTXSTS & (0xFFU << 16)) == 0U) - { - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - do - { - count++; - - if (count > 1000U) - { - break; - } - } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - } - } - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; - - if ((USBx_HOST->HPTXSTS & (0xFFU << 16)) == 0U) - { - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - do - { - count++; - - if (count > 1000U) - { - break; - } - } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - } - } - - return HAL_OK; -} - -/** - * @brief Initiate Do Ping protocol - * @param USBx Selected device - * @param hc_num Host Channel number - * This parameter can be a value from 1 to 15 - * @retval HAL state - */ -HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t chnum = (uint32_t)ch_num; - uint32_t num_packets = 1U; - uint32_t tmpreg; - - USBx_HC(chnum)->HCTSIZ = ((num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | - USB_OTG_HCTSIZ_DOPING; - - /* Set host channel enable */ - tmpreg = USBx_HC(chnum)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(chnum)->HCCHAR = tmpreg; - - return HAL_OK; -} - -/** - * @brief Stop Host Core - * @param USBx Selected device - * @retval HAL state - */ -HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t count = 0U; - uint32_t value; - uint32_t i; - - (void)USB_DisableGlobalInt(USBx); - - /* Flush USB FIFO */ - if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ - { - ret = HAL_ERROR; - } - - if (USB_FlushRxFifo(USBx) != HAL_OK) - { - ret = HAL_ERROR; - } - - /* Flush out any leftover queued requests. */ - for (i = 0U; i <= 15U; i++) - { - value = USBx_HC(i)->HCCHAR; - value |= USB_OTG_HCCHAR_CHDIS; - value &= ~USB_OTG_HCCHAR_CHENA; - value &= ~USB_OTG_HCCHAR_EPDIR; - USBx_HC(i)->HCCHAR = value; - } - - /* Halt all channels to put them into a known state. */ - for (i = 0U; i <= 15U; i++) - { - value = USBx_HC(i)->HCCHAR; - value |= USB_OTG_HCCHAR_CHDIS; - value |= USB_OTG_HCCHAR_CHENA; - value &= ~USB_OTG_HCCHAR_EPDIR; - USBx_HC(i)->HCCHAR = value; - - do - { - count++; - - if (count > 1000U) - { - break; - } - } while ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - - /* Clear any pending Host interrupts */ - USBx_HOST->HAINT = 0xFFFFFFFFU; - USBx->GINTSTS = 0xFFFFFFFFU; - - (void)USB_EnableGlobalInt(USBx); - - return ret; -} - -/** - * @brief USB_ActivateRemoteWakeup active remote wakeup signalling - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) - { - /* active Remote wakeup signalling */ - USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG; - } - - return HAL_OK; -} - -/** - * @brief USB_DeActivateRemoteWakeup de-active remote wakeup signalling - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* active Remote wakeup signalling */ - USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG); - - return HAL_OK; -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */ - -/** - * @} - */ +/** + ****************************************************************************** + * @file stm32f4xx_ll_usb.c + * @author MCD Application Team + * @brief USB Low Layer HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Initialization/de-initialization functions + * + I/O operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2016 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Fill parameters of Init structure in USB_OTG_CfgTypeDef structure. + + (#) Call USB_CoreInit() API to initialize the USB Core peripheral. + + (#) The upper HAL HCD/PCD driver will call the right routines for its internal processes. + + @endverbatim + + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_LL_USB_DRIVER + * @{ + */ + +#if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx); + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup USB_LL_Exported_Functions USB Low Layer Exported Functions + * @{ + */ + +/** @defgroup USB_LL_Exported_Functions_Group1 Initialization/de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization/de-initialization functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the USB Core + * @param USBx USB Instance + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + HAL_StatusTypeDef ret; + if (cfg.phy_itface == USB_OTG_ULPI_PHY) + { + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + + /* Init The ULPI Interface */ + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + /* Select vbus source */ + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + if (cfg.use_external_vbus == 1U) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_ULPIEVBUSD; + } + + /* Reset after a PHY select */ + ret = USB_CoreReset(USBx); + } + else /* FS interface (embedded Phy) */ + { + /* Select FS Embedded PHY */ + USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + + /* Reset after a PHY select */ + ret = USB_CoreReset(USBx); + + if (cfg.battery_charging_enable == 0U) + { + /* Activate the USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + else + { + /* Deactivate the USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + } + + if (cfg.dma_enable == 1U) + { + USBx->GAHBCFG |= USB_OTG_GAHBCFG_HBSTLEN_2; + USBx->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; + } + + return ret; +} + + +/** + * @brief Set the USB turnaround time + * @param USBx USB Instance + * @param hclk: AHB clock frequency + * @retval USB turnaround time In PHY Clocks number + */ +HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, + uint32_t hclk, uint8_t speed) +{ + uint32_t UsbTrd; + + /* The USBTRD is configured according to the tables below, depending on AHB frequency + used by application. In the low AHB frequency range it is used to stretch enough the USB response + time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access + latency to the Data FIFO */ + if (speed == USBD_FS_SPEED) + { + if ((hclk >= 14200000U) && (hclk < 15000000U)) + { + /* hclk Clock Range between 14.2-15 MHz */ + UsbTrd = 0xFU; + } + else if ((hclk >= 15000000U) && (hclk < 16000000U)) + { + /* hclk Clock Range between 15-16 MHz */ + UsbTrd = 0xEU; + } + else if ((hclk >= 16000000U) && (hclk < 17200000U)) + { + /* hclk Clock Range between 16-17.2 MHz */ + UsbTrd = 0xDU; + } + else if ((hclk >= 17200000U) && (hclk < 18500000U)) + { + /* hclk Clock Range between 17.2-18.5 MHz */ + UsbTrd = 0xCU; + } + else if ((hclk >= 18500000U) && (hclk < 20000000U)) + { + /* hclk Clock Range between 18.5-20 MHz */ + UsbTrd = 0xBU; + } + else if ((hclk >= 20000000U) && (hclk < 21800000U)) + { + /* hclk Clock Range between 20-21.8 MHz */ + UsbTrd = 0xAU; + } + else if ((hclk >= 21800000U) && (hclk < 24000000U)) + { + /* hclk Clock Range between 21.8-24 MHz */ + UsbTrd = 0x9U; + } + else if ((hclk >= 24000000U) && (hclk < 27700000U)) + { + /* hclk Clock Range between 24-27.7 MHz */ + UsbTrd = 0x8U; + } + else if ((hclk >= 27700000U) && (hclk < 32000000U)) + { + /* hclk Clock Range between 27.7-32 MHz */ + UsbTrd = 0x7U; + } + else /* if(hclk >= 32000000) */ + { + /* hclk Clock Range between 32-200 MHz */ + UsbTrd = 0x6U; + } + } + else if (speed == USBD_HS_SPEED) + { + UsbTrd = USBD_HS_TRDT_VALUE; + } + else + { + UsbTrd = USBD_DEFAULT_TRDT_VALUE; + } + + USBx->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + USBx->GUSBCFG |= (uint32_t)((UsbTrd << 10) & USB_OTG_GUSBCFG_TRDT); + + return HAL_OK; +} + +/** + * @brief USB_EnableGlobalInt + * Enables the controller's Global Int in the AHB Config reg + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx) +{ + USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + return HAL_OK; +} + +/** + * @brief USB_DisableGlobalInt + * Disable the controller's Global Int in the AHB Config reg + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx) +{ + USBx->GAHBCFG &= ~USB_OTG_GAHBCFG_GINT; + return HAL_OK; +} + +/** + * @brief USB_SetCurrentMode Set functional mode + * @param USBx Selected device + * @param mode current core mode + * This parameter can be one of these values: + * @arg USB_DEVICE_MODE Peripheral mode + * @arg USB_HOST_MODE Host mode + * @retval HAL status + */ +HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode) +{ + uint32_t ms = 0U; + + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); + + if (mode == USB_HOST_MODE) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_FHMOD; + + do + { + HAL_Delay(1U); + ms++; + } while ((USB_GetMode(USBx) != (uint32_t)USB_HOST_MODE) && (ms < 50U)); + } + else if (mode == USB_DEVICE_MODE) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + do + { + HAL_Delay(1U); + ms++; + } while ((USB_GetMode(USBx) != (uint32_t)USB_DEVICE_MODE) && (ms < 50U)); + } + else + { + return HAL_ERROR; + } + + if (ms == 50U) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief USB_DevInit Initializes the USB_OTG controller registers + * for device mode + * @param USBx Selected device + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + for (i = 0U; i < 15U; i++) + { + USBx->DIEPTXF[i] = 0U; + } + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* VBUS Sensing setup */ + if (cfg.vbus_sensing_enable == 0U) + { + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + + /* Deactivate VBUS Sensing B */ + USBx->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + /* B-peripheral session valid override enable */ + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + } + else + { + /* Enable HW VBUS sensing */ + USBx->GCCFG |= USB_OTG_GCCFG_VBDEN; + } +#else + /* VBUS Sensing setup */ + if (cfg.vbus_sensing_enable == 0U) + { + /* + * Disable HW VBUS sensing. VBUS is internally considered to be always + * at VBUS-Valid level (5V). + */ + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; + } + else + { + /* Enable HW VBUS sensing */ + USBx->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + + /* Restart the Phy Clock */ + USBx_PCGCCTL = 0U; + + /* Device mode configuration */ + USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; + + if (cfg.phy_itface == USB_OTG_ULPI_PHY) + { + if (cfg.speed == USBD_HS_SPEED) + { + /* Set Core speed to High speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH); + } + else + { + /* Set Core speed to Full speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH_IN_FULL); + } + } + else + { + /* Set Core speed to Full speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_FULL); + } + + /* Flush the FIFOs */ + if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ + { + ret = HAL_ERROR; + } + + if (USB_FlushRxFifo(USBx) != HAL_OK) + { + ret = HAL_ERROR; + } + + /* Clear all pending Device Interrupts */ + USBx_DEVICE->DIEPMSK = 0U; + USBx_DEVICE->DOEPMSK = 0U; + USBx_DEVICE->DAINTMSK = 0U; + + for (i = 0U; i < cfg.dev_endpoints; i++) + { + if ((USBx_INEP(i)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + if (i == 0U) + { + USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_SNAK; + } + else + { + USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_EPDIS | USB_OTG_DIEPCTL_SNAK; + } + } + else + { + USBx_INEP(i)->DIEPCTL = 0U; + } + + USBx_INEP(i)->DIEPTSIZ = 0U; + USBx_INEP(i)->DIEPINT = 0xFB7FU; + } + + for (i = 0U; i < cfg.dev_endpoints; i++) + { + if ((USBx_OUTEP(i)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + if (i == 0U) + { + USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_SNAK; + } + else + { + USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_EPDIS | USB_OTG_DOEPCTL_SNAK; + } + } + else + { + USBx_OUTEP(i)->DOEPCTL = 0U; + } + + USBx_OUTEP(i)->DOEPTSIZ = 0U; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + } + + USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); + + /* Disable all interrupts. */ + USBx->GINTMSK = 0U; + + /* Clear any pending interrupts */ + USBx->GINTSTS = 0xBFFFFFFFU; + + /* Enable the common interrupts */ + if (cfg.dma_enable == 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + /* Enable interrupts matching to the Device mode ONLY */ + USBx->GINTMSK |= USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_USBRST | + USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_IEPINT | + USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IISOIXFRM | + USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM; + + if (cfg.Sof_enable != 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_SOFM; + } + + if (cfg.vbus_sensing_enable == 1U) + { + USBx->GINTMSK |= (USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_OTGINT); + } + + return ret; +} + +/** + * @brief USB_FlushTxFifo Flush a Tx FIFO + * @param USBx Selected device + * @param num FIFO number + * This parameter can be a value from 1 to 15 + 15 means Flush all Tx FIFOs + * @retval HAL status + */ +HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num) +{ + __IO uint32_t count = 0U; + + /* Wait for AHB master IDLE state. */ + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); + + /* Flush TX Fifo */ + count = 0U; + USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (num << 6)); + + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + + return HAL_OK; +} + +/** + * @brief USB_FlushRxFifo Flush Rx FIFO + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx) +{ + __IO uint32_t count = 0U; + + /* Wait for AHB master IDLE state. */ + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); + + /* Flush RX Fifo */ + count = 0U; + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + return HAL_OK; +} + +/** + * @brief USB_SetDevSpeed Initializes the DevSpd field of DCFG register + * depending the PHY type and the enumeration speed of the device. + * @param USBx Selected device + * @param speed device speed + * This parameter can be one of these values: + * @arg USB_OTG_SPEED_HIGH: High speed mode + * @arg USB_OTG_SPEED_HIGH_IN_FULL: High speed core in Full Speed mode + * @arg USB_OTG_SPEED_FULL: Full speed mode + * @retval Hal status + */ +HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_DEVICE->DCFG |= speed; + return HAL_OK; +} + +/** + * @brief USB_GetDevSpeed Return the Dev Speed + * @param USBx Selected device + * @retval speed device speed + * This parameter can be one of these values: + * @arg USBD_HS_SPEED: High speed mode + * @arg USBD_FS_SPEED: Full speed mode + */ +uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t speed; + uint32_t DevEnumSpeed = USBx_DEVICE->DSTS & USB_OTG_DSTS_ENUMSPD; + + if (DevEnumSpeed == DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ) + { + speed = USBD_HS_SPEED; + } + else if ((DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ) || + (DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_48MHZ)) + { + speed = USBD_FS_SPEED; + } + else + { + speed = 0xFU; + } + + return speed; +} + +/** + * @brief Activate and configure an endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); + + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_USBAEP) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_USBAEP; + } + } + else + { + USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); + + if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DOEPCTL_USBAEP; + } + } + return HAL_OK; +} + +/** + * @brief Activate and configure a dedicated endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if (((USBx_INEP(epnum)->DIEPCTL) & USB_OTG_DIEPCTL_USBAEP) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_USBAEP; + } + + USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); + } + else + { + if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DOEPCTL_USBAEP; + } + + USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); + } + + return HAL_OK; +} + +/** + * @brief De-activate and de-initialize an endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; + } + + USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_USBAEP | + USB_OTG_DIEPCTL_MPSIZ | + USB_OTG_DIEPCTL_TXFNUM | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_EPTYP); + } + else + { + if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; + } + + USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_USBAEP | + USB_OTG_DOEPCTL_MPSIZ | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | + USB_OTG_DOEPCTL_EPTYP); + } + + return HAL_OK; +} + +/** + * @brief De-activate and de-initialize a dedicated endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; + } + + USBx_INEP(epnum)->DIEPCTL &= ~ USB_OTG_DIEPCTL_USBAEP; + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + } + else + { + if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; + } + + USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_USBAEP; + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + } + + return HAL_OK; +} + +/** + * @brief USB_EPStartXfer : setup and starts a transfer over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + uint16_t pktcnt; + + /* IN endpoint */ + if (ep->is_in == 1U) + { + /* Zero Length Packet? */ + if (ep->xfer_len == 0U) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + } + else + { + /* Program the transfer size and packet count + * as follows: xfersize = N * maxpacket + + * short_packet pktcnt = N + (short_packet + * exist ? 1 : 0) + */ + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & + (((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket) << 19)); + + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); + + if (ep->type == EP_TYPE_ISOC) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_MULCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_MULCNT & (1U << 29)); + } + } + + if (dma == 1U) + { + if ((uint32_t)ep->dma_addr != 0U) + { + USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); + } + + if (ep->type == EP_TYPE_ISOC) + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; + } + else + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } + } + + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + } + else + { + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + if (ep->type != EP_TYPE_ISOC) + { + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0U) + { + USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); + } + } + else + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; + } + else + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } + + (void)USB_WritePacket(USBx, ep->xfer_buff, ep->num, (uint16_t)ep->xfer_len, dma); + } + } + } + else /* OUT endpoint */ + { + /* Program the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); + + if (ep->xfer_len == 0U) + { + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->maxpacket); + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + } + else + { + pktcnt = (uint16_t)((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket); + ep->xfer_size = ep->maxpacket * pktcnt; + + USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_PKTCNT & ((uint32_t)pktcnt << 19); + USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_XFRSIZ & ep->xfer_size; + } + + if (dma == 1U) + { + if ((uint32_t)ep->xfer_buff != 0U) + { + USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); + } + } + + if (ep->type == EP_TYPE_ISOC) + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SODDFRM; + } + else + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; + } + } + /* EP enable */ + USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); + } + + return HAL_OK; +} + +/** + * @brief USB_EP0StartXfer : setup and starts a transfer over the EP 0 + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* IN endpoint */ + if (ep->is_in == 1U) + { + /* Zero Length Packet? */ + if (ep->xfer_len == 0U) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + } + else + { + /* Program the transfer size and packet count + * as follows: xfersize = N * maxpacket + + * short_packet pktcnt = N + (short_packet + * exist ? 1 : 0) + */ + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + + if (ep->xfer_len > ep->maxpacket) + { + ep->xfer_len = ep->maxpacket; + } + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); + } + + if (dma == 1U) + { + if ((uint32_t)ep->dma_addr != 0U) + { + USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); + } + + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + } + else + { + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0U) + { + USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); + } + } + } + else /* OUT endpoint */ + { + /* Program the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); + + if (ep->xfer_len > 0U) + { + ep->xfer_len = ep->maxpacket; + } + + /* Store transfer size, for EP0 this is equal to endpoint max packet size */ + ep->xfer_size = ep->maxpacket; + + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->xfer_size); + + if (dma == 1U) + { + if ((uint32_t)ep->xfer_buff != 0U) + { + USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); + } + } + + /* EP enable */ + USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); + } + + return HAL_OK; +} + + +/** + * @brief USB_EPStoptXfer Stop transfer on an EP + * @param USBx usb device instance + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPStopXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + + /* IN endpoint */ + if (ep->is_in == 1U) + { + /* EP enable, IN data in FIFO */ + if (((USBx_INEP(ep->num)->DIEPCTL) & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + USBx_INEP(ep->num)->DIEPCTL |= (USB_OTG_DIEPCTL_SNAK); + USBx_INEP(ep->num)->DIEPCTL |= (USB_OTG_DIEPCTL_EPDIS); + + do + { + count++; + + if (count > 10000U) + { + ret = HAL_ERROR; + break; + } + } while (((USBx_INEP(ep->num)->DIEPCTL) & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA); + } + } + else /* OUT endpoint */ + { + if (((USBx_OUTEP(ep->num)->DOEPCTL) & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + USBx_OUTEP(ep->num)->DOEPCTL |= (USB_OTG_DOEPCTL_SNAK); + USBx_OUTEP(ep->num)->DOEPCTL |= (USB_OTG_DOEPCTL_EPDIS); + + do + { + count++; + + if (count > 10000U) + { + ret = HAL_ERROR; + break; + } + } while (((USBx_OUTEP(ep->num)->DOEPCTL) & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA); + } + } + + return ret; +} + + +/** + * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated + * with the EP/channel + * @param USBx Selected device + * @param src pointer to source buffer + * @param ch_ep_num endpoint or host channel number + * @param len Number of bytes to write + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, + uint8_t ch_ep_num, uint16_t len, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t *pSrc = src; + uint32_t count32b; + uint32_t i; + + if (dma == 0U) + { + count32b = ((uint32_t)len + 3U) / 4U; + for (i = 0U; i < count32b; i++) + { + USBx_DFIFO((uint32_t)ch_ep_num) = __UNALIGNED_UINT32_READ(pSrc); + pSrc++; + pSrc++; + pSrc++; + pSrc++; + } + } + + return HAL_OK; +} + +/** + * @brief USB_ReadPacket : read a packet from the RX FIFO + * @param USBx Selected device + * @param dest source pointer + * @param len Number of bytes to read + * @retval pointer to destination buffer + */ +void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t *pDest = dest; + uint32_t pData; + uint32_t i; + uint32_t count32b = (uint32_t)len >> 2U; + uint16_t remaining_bytes = len % 4U; + + for (i = 0U; i < count32b; i++) + { + __UNALIGNED_UINT32_WRITE(pDest, USBx_DFIFO(0U)); + pDest++; + pDest++; + pDest++; + pDest++; + } + + /* When Number of data is not word aligned, read the remaining byte */ + if (remaining_bytes != 0U) + { + i = 0U; + __UNALIGNED_UINT32_WRITE(&pData, USBx_DFIFO(0U)); + + do + { + *(uint8_t *)pDest = (uint8_t)(pData >> (8U * (uint8_t)(i))); + i++; + pDest++; + remaining_bytes--; + } while (remaining_bytes != 0U); + } + + return ((void *)pDest); +} + +/** + * @brief USB_EPSetStall : set a stall condition over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + if (((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == 0U) && (epnum != 0U)) + { + USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_EPDIS); + } + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_STALL; + } + else + { + if (((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == 0U) && (epnum != 0U)) + { + USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_EPDIS); + } + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_STALL; + } + + return HAL_OK; +} + +/** + * @brief USB_EPClearStall : Clear a stall condition over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + USBx_INEP(epnum)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; /* DATA0 */ + } + } + else + { + USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; /* DATA0 */ + } + } + return HAL_OK; +} + +/** + * @brief USB_StopDevice : Stop the usb device mode + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx) +{ + HAL_StatusTypeDef ret; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + /* Clear Pending interrupt */ + for (i = 0U; i < 15U; i++) + { + USBx_INEP(i)->DIEPINT = 0xFB7FU; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + } + + /* Clear interrupt masks */ + USBx_DEVICE->DIEPMSK = 0U; + USBx_DEVICE->DOEPMSK = 0U; + USBx_DEVICE->DAINTMSK = 0U; + + /* Flush the FIFO */ + ret = USB_FlushRxFifo(USBx); + if (ret != HAL_OK) + { + return ret; + } + + ret = USB_FlushTxFifo(USBx, 0x10U); + if (ret != HAL_OK) + { + return ret; + } + + return ret; +} + +/** + * @brief USB_SetDevAddress : Stop the usb device mode + * @param USBx Selected device + * @param address new device address to be assigned + * This parameter can be a value from 0 to 255 + * @retval HAL status + */ +HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_DEVICE->DCFG &= ~(USB_OTG_DCFG_DAD); + USBx_DEVICE->DCFG |= ((uint32_t)address << 4) & USB_OTG_DCFG_DAD; + + return HAL_OK; +} + +/** + * @brief USB_DevConnect : Connect the USB device by enabling Rpu + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* In case phy is stopped, ensure to ungate and restore the phy CLK */ + USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); + + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; + + return HAL_OK; +} + +/** + * @brief USB_DevDisconnect : Disconnect the USB device by disabling Rpu + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* In case phy is stopped, ensure to ungate and restore the phy CLK */ + USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); + + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + + return HAL_OK; +} + +/** + * @brief USB_ReadInterrupts: return the global USB interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t tmpreg; + + tmpreg = USBx->GINTSTS; + tmpreg &= USBx->GINTMSK; + + return tmpreg; +} + +/** + * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_DEVICE->DAINT; + tmpreg &= USBx_DEVICE->DAINTMSK; + + return ((tmpreg & 0xffff0000U) >> 16); +} + +/** + * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_DEVICE->DAINT; + tmpreg &= USBx_DEVICE->DAINTMSK; + + return ((tmpreg & 0xFFFFU)); +} + +/** + * @brief Returns Device OUT EP Interrupt register + * @param USBx Selected device + * @param epnum endpoint number + * This parameter can be a value from 0 to 15 + * @retval Device OUT EP Interrupt register + */ +uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_OUTEP((uint32_t)epnum)->DOEPINT; + tmpreg &= USBx_DEVICE->DOEPMSK; + + return tmpreg; +} + +/** + * @brief Returns Device IN EP Interrupt register + * @param USBx Selected device + * @param epnum endpoint number + * This parameter can be a value from 0 to 15 + * @retval Device IN EP Interrupt register + */ +uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + uint32_t msk; + uint32_t emp; + + msk = USBx_DEVICE->DIEPMSK; + emp = USBx_DEVICE->DIEPEMPMSK; + msk |= ((emp >> (epnum & EP_ADDR_MSK)) & 0x1U) << 7; + tmpreg = USBx_INEP((uint32_t)epnum)->DIEPINT & msk; + + return tmpreg; +} + +/** + * @brief USB_ClearInterrupts: clear a USB interrupt + * @param USBx Selected device + * @param interrupt flag + * @retval None + */ +void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt) +{ + USBx->GINTSTS |= interrupt; +} + +/** + * @brief Returns USB core mode + * @param USBx Selected device + * @retval return core mode : Host or Device + * This parameter can be one of these values: + * 0 : Host + * 1 : Device + */ +uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx) +{ + return ((USBx->GINTSTS) & 0x1U); +} + +/** + * @brief Activate EP0 for Setup transactions + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* Set the MPS of the IN EP0 to 64 bytes */ + USBx_INEP(0U)->DIEPCTL &= ~USB_OTG_DIEPCTL_MPSIZ; + + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; + + return HAL_OK; +} + +/** + * @brief Prepare the EP0 to start the first control setup + * @param USBx Selected device + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @param psetup pointer to setup packet + * @retval HAL status + */ +HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + + if (gSNPSiD > USB_OTG_CORE_ID_300A) + { + if ((USBx_OUTEP(0U)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + return HAL_OK; + } + } + + USBx_OUTEP(0U)->DOEPTSIZ = 0U; + USBx_OUTEP(0U)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + USBx_OUTEP(0U)->DOEPTSIZ |= (3U * 8U); + USBx_OUTEP(0U)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_STUPCNT; + + if (dma == 1U) + { + USBx_OUTEP(0U)->DOEPDMA = (uint32_t)psetup; + /* EP enable */ + USBx_OUTEP(0U)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_USBAEP; + } + + return HAL_OK; +} + +/** + * @brief Reset the USB Core (needed after USB clock settings change) + * @param USBx Selected device + * @retval HAL status + */ +static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx) +{ + __IO uint32_t count = 0U; + + /* Wait for AHB master IDLE state. */ + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); + + /* Core Soft Reset */ + count = 0U; + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + + do + { + count++; + + if (count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + + return HAL_OK; +} + +/** + * @brief USB_HostInit : Initializes the USB OTG controller registers + * for Host mode + * @param USBx Selected device + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + /* Restart the Phy Clock */ + USBx_PCGCCTL = 0U; + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Disable HW VBUS sensing */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); +#else + /* + * Disable HW VBUS sensing. VBUS is internally considered to be always + * at VBUS-Valid level (5V). + */ + USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Disable Battery chargin detector */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); +#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + + if ((USBx->CID & (0x1U << 8)) != 0U) + { + if (cfg.speed == USBH_FSLS_SPEED) + { + /* Force Device Enumeration to FS/LS mode only */ + USBx_HOST->HCFG |= USB_OTG_HCFG_FSLSS; + } + else + { + /* Set default Max speed support */ + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); + } + } + else + { + /* Set default Max speed support */ + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); + } + + /* Make sure the FIFOs are flushed. */ + if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ + { + ret = HAL_ERROR; + } + + if (USB_FlushRxFifo(USBx) != HAL_OK) + { + ret = HAL_ERROR; + } + + /* Clear all pending HC Interrupts */ + for (i = 0U; i < cfg.Host_channels; i++) + { + USBx_HC(i)->HCINT = 0xFFFFFFFFU; + USBx_HC(i)->HCINTMSK = 0U; + } + + /* Disable all interrupts. */ + USBx->GINTMSK = 0U; + + /* Clear any pending interrupts */ + USBx->GINTSTS = 0xFFFFFFFFU; + + if ((USBx->CID & (0x1U << 8)) != 0U) + { + /* set Rx FIFO size */ + USBx->GRXFSIZ = 0x200U; + USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x100U << 16) & USB_OTG_NPTXFD) | 0x200U); + USBx->HPTXFSIZ = (uint32_t)(((0xE0U << 16) & USB_OTG_HPTXFSIZ_PTXFD) | 0x300U); + } + else + { + /* set Rx FIFO size */ + USBx->GRXFSIZ = 0x80U; + USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x60U << 16) & USB_OTG_NPTXFD) | 0x80U); + USBx->HPTXFSIZ = (uint32_t)(((0x40U << 16)& USB_OTG_HPTXFSIZ_PTXFD) | 0xE0U); + } + + /* Enable the common interrupts */ + if (cfg.dma_enable == 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + /* Enable interrupts matching to the Host mode ONLY */ + USBx->GINTMSK |= (USB_OTG_GINTMSK_PRTIM | USB_OTG_GINTMSK_HCIM | \ + USB_OTG_GINTMSK_SOFM | USB_OTG_GINTSTS_DISCINT | \ + USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM); + + return ret; +} + +/** + * @brief USB_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the + * HCFG register on the PHY type and set the right frame interval + * @param USBx Selected device + * @param freq clock frequency + * This parameter can be one of these values: + * HCFG_48_MHZ : Full Speed 48 MHz Clock + * HCFG_6_MHZ : Low Speed 6 MHz Clock + * @retval HAL status + */ +HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSPCS); + USBx_HOST->HCFG |= (uint32_t)freq & USB_OTG_HCFG_FSLSPCS; + + if (freq == HCFG_48_MHZ) + { + USBx_HOST->HFIR = 48000U; + } + else if (freq == HCFG_6_MHZ) + { + USBx_HOST->HFIR = 6000U; + } + else + { + /* ... */ + } + + return HAL_OK; +} + +/** + * @brief USB_OTG_ResetPort : Reset Host Port + * @param USBx Selected device + * @retval HAL status + * @note (1)The application must wait at least 10 ms + * before clearing the reset bit. + */ +HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + + hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | + USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); + + USBx_HPRT0 = (USB_OTG_HPRT_PRST | hprt0); + HAL_Delay(100U); /* See Note #1 */ + USBx_HPRT0 = ((~USB_OTG_HPRT_PRST) & hprt0); + HAL_Delay(10U); + + return HAL_OK; +} + +/** + * @brief USB_DriveVbus : activate or de-activate vbus + * @param state VBUS state + * This parameter can be one of these values: + * 0 : Deactivate VBUS + * 1 : Activate VBUS + * @retval HAL status + */ +HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + + hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | + USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); + + if (((hprt0 & USB_OTG_HPRT_PPWR) == 0U) && (state == 1U)) + { + USBx_HPRT0 = (USB_OTG_HPRT_PPWR | hprt0); + } + if (((hprt0 & USB_OTG_HPRT_PPWR) == USB_OTG_HPRT_PPWR) && (state == 0U)) + { + USBx_HPRT0 = ((~USB_OTG_HPRT_PPWR) & hprt0); + } + return HAL_OK; +} + +/** + * @brief Return Host Core speed + * @param USBx Selected device + * @retval speed : Host speed + * This parameter can be one of these values: + * @arg HCD_SPEED_HIGH: High speed mode + * @arg HCD_SPEED_FULL: Full speed mode + * @arg HCD_SPEED_LOW: Low speed mode + */ +uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + return ((hprt0 & USB_OTG_HPRT_PSPD) >> 17); +} + +/** + * @brief Return Host Current Frame number + * @param USBx Selected device + * @retval current frame number + */ +uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + return (USBx_HOST->HFNUM & USB_OTG_HFNUM_FRNUM); +} + +/** + * @brief Initialize a host channel + * @param USBx Selected device + * @param ch_num Channel number + * This parameter can be a value from 1 to 15 + * @param epnum Endpoint number + * This parameter can be a value from 1 to 15 + * @param dev_address Current device address + * This parameter can be a value from 0 to 255 + * @param speed Current device speed + * This parameter can be one of these values: + * @arg USB_OTG_SPEED_HIGH: High speed mode + * @arg USB_OTG_SPEED_FULL: Full speed mode + * @arg USB_OTG_SPEED_LOW: Low speed mode + * @param ep_type Endpoint Type + * This parameter can be one of these values: + * @arg EP_TYPE_CTRL: Control type + * @arg EP_TYPE_ISOC: Isochronous type + * @arg EP_TYPE_BULK: Bulk type + * @arg EP_TYPE_INTR: Interrupt type + * @param mps Max Packet Size + * This parameter can be a value from 0 to 32K + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, + uint8_t epnum, uint8_t dev_address, uint8_t speed, + uint8_t ep_type, uint16_t mps) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t HCcharEpDir; + uint32_t HCcharLowSpeed; + uint32_t HostCoreSpeed; + + /* Clear old interrupt conditions for this host channel. */ + USBx_HC((uint32_t)ch_num)->HCINT = 0xFFFFFFFFU; + + /* Enable channel interrupts required for this transfer. */ + switch (ep_type) + { + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_STALLM | + USB_OTG_HCINTMSK_TXERRM | + USB_OTG_HCINTMSK_DTERRM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_NAKM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; + } + else + { + if ((USBx->CID & (0x1U << 8)) != 0U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_NYET | + USB_OTG_HCINTMSK_ACKM; + } + } + break; + + case EP_TYPE_INTR: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_STALLM | + USB_OTG_HCINTMSK_TXERRM | + USB_OTG_HCINTMSK_DTERRM | + USB_OTG_HCINTMSK_NAKM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_FRMORM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; + } + + break; + + case EP_TYPE_ISOC: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_ACKM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_FRMORM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_TXERRM | USB_OTG_HCINTMSK_BBERRM); + } + break; + + default: + ret = HAL_ERROR; + break; + } + + /* Enable host channel Halt interrupt */ + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_CHHM; + + /* Enable the top level host channel interrupt. */ + USBx_HOST->HAINTMSK |= 1UL << (ch_num & 0xFU); + + /* Make sure host channel interrupts are enabled. */ + USBx->GINTMSK |= USB_OTG_GINTMSK_HCIM; + + /* Program the HCCHAR register */ + if ((epnum & 0x80U) == 0x80U) + { + HCcharEpDir = (0x1U << 15) & USB_OTG_HCCHAR_EPDIR; + } + else + { + HCcharEpDir = 0U; + } + + HostCoreSpeed = USB_GetHostSpeed(USBx); + + /* LS device plugged to HUB */ + if ((speed == HPRT0_PRTSPD_LOW_SPEED) && (HostCoreSpeed != HPRT0_PRTSPD_LOW_SPEED)) + { + HCcharLowSpeed = (0x1U << 17) & USB_OTG_HCCHAR_LSDEV; + } + else + { + HCcharLowSpeed = 0U; + } + + USBx_HC((uint32_t)ch_num)->HCCHAR = (((uint32_t)dev_address << 22) & USB_OTG_HCCHAR_DAD) | + ((((uint32_t)epnum & 0x7FU) << 11) & USB_OTG_HCCHAR_EPNUM) | + (((uint32_t)ep_type << 18) & USB_OTG_HCCHAR_EPTYP) | + ((uint32_t)mps & USB_OTG_HCCHAR_MPSIZ) | HCcharEpDir | HCcharLowSpeed; + + if ((ep_type == EP_TYPE_INTR) || (ep_type == EP_TYPE_ISOC)) + { + USBx_HC((uint32_t)ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM; + } + + return ret; +} + +/** + * @brief Start a transfer over a host channel + * @param USBx Selected device + * @param hc pointer to host channel structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t ch_num = (uint32_t)hc->ch_num; + __IO uint32_t tmpreg; + uint8_t is_oddframe; + uint16_t len_words; + uint16_t num_packets; + uint16_t max_hc_pkt_count = 256U; + + if (((USBx->CID & (0x1U << 8)) != 0U) && (hc->speed == USBH_HS_SPEED)) + { + /* in DMA mode host Core automatically issues ping in case of NYET/NAK */ + if ((dma == 1U) && ((hc->ep_type == EP_TYPE_CTRL) || (hc->ep_type == EP_TYPE_BULK))) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK &= ~(USB_OTG_HCINTMSK_NYET | + USB_OTG_HCINTMSK_ACKM | + USB_OTG_HCINTMSK_NAKM); + } + + if ((dma == 0U) && (hc->do_ping == 1U)) + { + (void)USB_DoPing(USBx, hc->ch_num); + return HAL_OK; + } + + } + + /* Compute the expected number of packets associated to the transfer */ + if (hc->xfer_len > 0U) + { + num_packets = (uint16_t)((hc->xfer_len + hc->max_packet - 1U) / hc->max_packet); + + if (num_packets > max_hc_pkt_count) + { + num_packets = max_hc_pkt_count; + hc->XferSize = (uint32_t)num_packets * hc->max_packet; + } + } + else + { + num_packets = 1U; + } + + /* + * For IN channel HCTSIZ.XferSize is expected to be an integer multiple of + * max_packet size. + */ + if (hc->ep_is_in != 0U) + { + hc->XferSize = (uint32_t)num_packets * hc->max_packet; + } + else + { + hc->XferSize = hc->xfer_len; + } + + /* Initialize the HCTSIZn register */ + USBx_HC(ch_num)->HCTSIZ = (hc->XferSize & USB_OTG_HCTSIZ_XFRSIZ) | + (((uint32_t)num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | + (((uint32_t)hc->data_pid << 29) & USB_OTG_HCTSIZ_DPID); + + if (dma != 0U) + { + /* xfer_buff MUST be 32-bits aligned */ + USBx_HC(ch_num)->HCDMA = (uint32_t)hc->xfer_buff; + } + + is_oddframe = (((uint32_t)USBx_HOST->HFNUM & 0x01U) != 0U) ? 0U : 1U; + USBx_HC(ch_num)->HCCHAR &= ~USB_OTG_HCCHAR_ODDFRM; + USBx_HC(ch_num)->HCCHAR |= (uint32_t)is_oddframe << 29; + + /* Set host channel enable */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + + /* make sure to set the correct ep direction */ + if (hc->ep_is_in != 0U) + { + tmpreg |= USB_OTG_HCCHAR_EPDIR; + } + else + { + tmpreg &= ~USB_OTG_HCCHAR_EPDIR; + } + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + + if (dma != 0U) /* dma mode */ + { + return HAL_OK; + } + + if ((hc->ep_is_in == 0U) && (hc->xfer_len > 0U)) + { + switch (hc->ep_type) + { + /* Non periodic transfer */ + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + + len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); + + /* check if there is enough space in FIFO space */ + if (len_words > (USBx->HNPTXSTS & 0xFFFFU)) + { + /* need to process data in nptxfempty interrupt */ + USBx->GINTMSK |= USB_OTG_GINTMSK_NPTXFEM; + } + break; + + /* Periodic transfer */ + case EP_TYPE_INTR: + case EP_TYPE_ISOC: + len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); + /* check if there is enough space in FIFO space */ + if (len_words > (USBx_HOST->HPTXSTS & 0xFFFFU)) /* split the transfer */ + { + /* need to process data in ptxfempty interrupt */ + USBx->GINTMSK |= USB_OTG_GINTMSK_PTXFEM; + } + break; + + default: + break; + } + + /* Write packet into the Tx FIFO. */ + (void)USB_WritePacket(USBx, hc->xfer_buff, hc->ch_num, (uint16_t)hc->xfer_len, 0); + } + + return HAL_OK; +} + +/** + * @brief Read all host channel interrupts status + * @param USBx Selected device + * @retval HAL state + */ +uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + return ((USBx_HOST->HAINT) & 0xFFFFU); +} + +/** + * @brief Halt a host channel + * @param USBx Selected device + * @param hc_num Host Channel number + * This parameter can be a value from 1 to 15 + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t hcnum = (uint32_t)hc_num; + __IO uint32_t count = 0U; + uint32_t HcEpType = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_EPTYP) >> 18; + uint32_t ChannelEna = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) >> 31; + + if (((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == USB_OTG_GAHBCFG_DMAEN) && + (ChannelEna == 0U)) + { + return HAL_OK; + } + + /* Check for space in the request queue to issue the halt. */ + if ((HcEpType == HCCHAR_CTRL) || (HcEpType == HCCHAR_BULK)) + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; + + if ((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == 0U) + { + if ((USBx->HNPTXSTS & (0xFFU << 16)) == 0U) + { + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + do + { + count++; + + if (count > 1000U) + { + break; + } + } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + } + } + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; + + if ((USBx_HOST->HPTXSTS & (0xFFU << 16)) == 0U) + { + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + do + { + count++; + + if (count > 1000U) + { + break; + } + } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + } + } + + return HAL_OK; +} + +/** + * @brief Initiate Do Ping protocol + * @param USBx Selected device + * @param hc_num Host Channel number + * This parameter can be a value from 1 to 15 + * @retval HAL state + */ +HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t chnum = (uint32_t)ch_num; + uint32_t num_packets = 1U; + uint32_t tmpreg; + + USBx_HC(chnum)->HCTSIZ = ((num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | + USB_OTG_HCTSIZ_DOPING; + + /* Set host channel enable */ + tmpreg = USBx_HC(chnum)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(chnum)->HCCHAR = tmpreg; + + return HAL_OK; +} + +/** + * @brief Stop Host Core + * @param USBx Selected device + * @retval HAL state + */ +HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t count = 0U; + uint32_t value; + uint32_t i; + + (void)USB_DisableGlobalInt(USBx); + + /* Flush USB FIFO */ + if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ + { + ret = HAL_ERROR; + } + + if (USB_FlushRxFifo(USBx) != HAL_OK) + { + ret = HAL_ERROR; + } + + /* Flush out any leftover queued requests. */ + for (i = 0U; i <= 15U; i++) + { + value = USBx_HC(i)->HCCHAR; + value |= USB_OTG_HCCHAR_CHDIS; + value &= ~USB_OTG_HCCHAR_CHENA; + value &= ~USB_OTG_HCCHAR_EPDIR; + USBx_HC(i)->HCCHAR = value; + } + + /* Halt all channels to put them into a known state. */ + for (i = 0U; i <= 15U; i++) + { + value = USBx_HC(i)->HCCHAR; + value |= USB_OTG_HCCHAR_CHDIS; + value |= USB_OTG_HCCHAR_CHENA; + value &= ~USB_OTG_HCCHAR_EPDIR; + USBx_HC(i)->HCCHAR = value; + + do + { + count++; + + if (count > 1000U) + { + break; + } + } while ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + + /* Clear any pending Host interrupts */ + USBx_HOST->HAINT = 0xFFFFFFFFU; + USBx->GINTSTS = 0xFFFFFFFFU; + + (void)USB_EnableGlobalInt(USBx); + + return ret; +} + +/** + * @brief USB_ActivateRemoteWakeup active remote wakeup signalling + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) + { + /* active Remote wakeup signalling */ + USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG; + } + + return HAL_OK; +} + +/** + * @brief USB_DeActivateRemoteWakeup de-active remote wakeup signalling + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* active Remote wakeup signalling */ + USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG); + + return HAL_OK; +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */ + +/** + * @} + */ diff --git a/Makefile b/Makefile index e40ffd5..e49d192 100644 --- a/Makefile +++ b/Makefile @@ -1,5 +1,5 @@ ########################################################################################################################## -# File automatically-generated by tool: [projectgenerator] version: [4.2.0-B44] date: [Tue Jan 02 00:01:05 EST 2024] +# File automatically-generated by tool: [projectgenerator] version: [4.2.0-B44] date: [Fri May 31 19:36:02 EDT 2024] ########################################################################################################################## # ------------------------------------------------ @@ -51,6 +51,7 @@ Drivers/Embedded-Base/general/src/ltc68041.c \ Drivers/Embedded-Base/general/src/sht30.c \ Drivers/Embedded-Base/middleware/src/timer.c \ Drivers/Embedded-Base/middleware/src/ringbuffer.c \ +Drivers/Embedded-Base/middleware/src/c_utils.c \ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c \ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c \ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c \ @@ -74,7 +75,11 @@ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c \ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c \ Core/Src/system_stm32f4xx.c \ Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c \ -Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c +Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c \ +Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c \ +Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c \ +Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c \ +Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c # ASM sources ASM_SOURCES = \ diff --git a/README.md b/README.md index c445626..4ac0d19 100644 --- a/README.md +++ b/README.md @@ -2,76 +2,13 @@ Our from-scratch Battery Management System application, v2. ## Setting up Docker Environment -> For initial installation, visit here: https://nerdocs.atlassian.net/wiki/spaces/NER/pages/108888108/Setting+Up+STM32+Dev+Env +> For initial installation and more info, visit here: https://nerdocs.atlassian.net/wiki/spaces/NER/pages/108888108/Setting+Up+STM32+Dev+Env ``` # TLDR: # Pull Container: -docker pull nwdepatie/ner-gcc-arm +docker compose pull # Run Container -# macOS: -docker run --rm -it --privileged -v "$PWD:/home/app" nwdepatie/ner-gcc-arm:latest bash - -# Windows: -docker run --rm -it --privileged -v "%cd%:/home/app" nwdepatie/ner-gcc-arm:latest bash -# or -docker run --rm -it --privileged -v "$(PWD):/home/app" nwdepatie/ner-gcc-arm:latest bash - -# Linux: -sudo docker run --rm -it --privileged -v "$PWD:/home/app" nwdepatie/ner-gcc-arm:latest bash -``` - -## Container Tools and Utilities -> This container is packed with tools that can be utilized by developers to give them more insight into their developed software, we've used bash aliases to make the commands more compact for ease of use -``` -## Tools / Utils - -# to build project -make all - -# to run Renode emulation -emulate -start -# Actual command is: -# renode cerberus.resc - -# to open a serial port with Rasberry Pi Probe (make sure /dev/tty0/ACM0 exists first) -serial -# Actual command is: -# minicom -b 115200 -o -D /dev/ttyACM0 - -# to flash STM board with Raspberry Pi Probe (WIP) -flash -# Actual command is: -# openocd -f interface/cmsis-dap.cfg -f target/stm32f4x.cfg -c "adapter speed 5000" -c "program ./build/cerberus.elf verify reset exit" - -# to autoformat code -clang-format -style=file -i whateverfile.c -``` -### Mounting Hardware to Docker Container in Windows -> Very specific use case but nonetheless needed, also documented in the above confluence page, on macOS and Linux this happens by default when running privileged docker container - -**We now have a Python script to automatically mount hardware! Run:** `python3 mount.py` - -For manually mounting, follow the process below: -``` -# Connect probe and open two terminals - -# Terminal 1: -wsl -d ubuntu - -# Terminal 2 -usbipd wsl list -usbipd wsl attach --distribution=ubuntu --busid= # Terminal might need to be elevated to admin privileges for this - -# Close the other wsl window, the device should be mounted to any WSL instance -# Start docker container -``` -## Building Docker Container -> Typically this isn't needed unless making local changes to Dockerfile, please default to the first method via pulling the docker container -``` -# if need to rebuild image -sudo docker image prune -a -sudo docker build -f ./Dockerfile -t ner-gcc-arm . +docker compose run --rm ner-gcc-arm ``` diff --git a/STM32F405RGTx_FLASH.ld b/STM32F405RGTx_FLASH.ld index 1eb7104..6f1d7fe 100644 --- a/STM32F405RGTx_FLASH.ld +++ b/STM32F405RGTx_FLASH.ld @@ -1,209 +1,209 @@ -/* -****************************************************************************** -** - -** File : LinkerScript.ld -** -** Author : STM32CubeMX -** -** Abstract : Linker script for STM32F405RGTx series -** 1024Kbytes FLASH and 192Kbytes RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** Distribution: The file is distributed “as is,” without any warranty -** of any kind. -** -***************************************************************************** -** @attention -** -**

© COPYRIGHT(c) 2019 STMicroelectronics

-** -** 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 of STMicroelectronics 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 HOLDER 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. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of RAM */ -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0x200; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -CCMRAM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K -FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >FLASH - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM AT> FLASH - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(8); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(8); - } >RAM - - - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - +/* +****************************************************************************** +** + +** File : LinkerScript.ld +** +** Author : STM32CubeMX +** +** Abstract : Linker script for STM32F405RGTx series +** 1024Kbytes FLASH and 192Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 STMicroelectronics

+** +** 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 of STMicroelectronics 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 HOLDER 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. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/art b/art new file mode 100644 index 0000000..f2ebd0d --- /dev/null +++ b/art @@ -0,0 +1,5 @@ + ______ __ __ ______ ______ __ __ ______ ______ _____ +/\ ___\ /\ \_\ \ /\ ___\ /\ == \ /\ \_\ \ /\ ___\ /\ == \ /\ __-. +\ \___ \ \ \ __ \ \ \ __\ \ \ _-/ \ \ __ \ \ \ __\ \ \ __< \ \ \/\ \ + \/\_____\ \ \_\ \_\ \ \_____\ \ \_\ \ \_\ \_\ \ \_____\ \ \_\ \_\ \ \____- + \/_____/ \/_/\/_/ \/_____/ \/_/ \/_/\/_/ \/_____/ \/_/ /_/ \/____/ diff --git a/compose.yml b/compose.yml new file mode 100644 index 0000000..0711112 --- /dev/null +++ b/compose.yml @@ -0,0 +1,22 @@ +name: shepherd + +services: + ner-gcc-arm: + image: ghcr.io/northeastern-electric-racing/embedded-base:main + build: . + network_mode: host + privileged: true + volumes: + - type: bind + source: . + target: /home/app + tty: true + expose: + - "3240" + environment: + - DEBUG_PORT=/dev/ttyACM0 + - STM_TARGET_NAME=stm32f4 + - USBIP_PORT=1-1.4 + devices: + - "/dev/ttyACM0:/dev/ttyACM0" + diff --git a/mount.py b/mount.py deleted file mode 100644 index a0ac99f..0000000 --- a/mount.py +++ /dev/null @@ -1,32 +0,0 @@ -import subprocess as sub -import os - -dvline = 0 - -#Function to get BUSID base on device name -def filter_name(x): - if "CMSIS-DAP" in x: - return True - else: - return False - -#This opens terminal 1 -os.system('start cmd.exe @cmd /c wsl -d ubuntu @cmd exit') - -#These helps filter out the BUSID -output = str(sub.getoutput("usbipd wsl list")) -linedvs = output.splitlines() #Split lines of output base on device name - -flt_busid = filter(filter_name, linedvs) -for x in flt_busid: - dvline = x #Obtain the line of specific device - -if dvline != 0: - dvid = dvline.split(" ", 1)[0] #Keep only the BUSID in the line - busid = str(dvid) #BUSID turn for list to single string - - #This opens Terminal 2 - #Terminal might need to be elevated to admin privileges for this - sub.check_call('cmd /k usbipd wsl attach --distribution=ubuntu --busid=' + busid) -else: - sub.check_call('cmd /k @echo "Probe not found"') \ No newline at end of file diff --git a/segment_testing/src/config.h b/segment_testing/src/config.h index 40de19a..1fa635b 100644 --- a/segment_testing/src/config.h +++ b/segment_testing/src/config.h @@ -5,7 +5,7 @@ #define CELLS_S 10 #define CELLS_P 7 #define THERMISTORS 11 -#define CHIPS 2 +#define CHIPS 12 // DATA COLLECTION RATES #define VOLT_DELAY 500 diff --git a/segment_testing/src/main.cpp b/segment_testing/src/main.cpp index 18c820d..3fd99f8 100644 --- a/segment_testing/src/main.cpp +++ b/segment_testing/src/main.cpp @@ -28,6 +28,15 @@ uint64_t lastPrintTime = 0; uint64_t lastVoltTime = 0; uint64_t lastTempTime = 0; +const uint32_t VOLT_TEMP_CONV[106] = { +157300, 148800, 140300, 131800, 123300, 114800, 108772, 102744, 96716, 90688, 84660, 80328, 75996, 71664, 67332, +63000, 59860, 56720, 53580, 50440, 47300, 45004, 42708, 40412, 38116, 35820, 34124, 32428, 30732, 29036, 27340, +26076, 24812, 23548, 22284, 21020, 20074, 19128, 18182, 17236, 16290, 15576, 14862, 14148, 13434, 12720, 12176, +11632, 11088, 10544, 10000, 9584, 9168, 8753, 8337, 7921, 7600, 7279, 6957, 6636, 6315, 6065, 5816, 5566, 5317, +5067, 4872, 4676, 4481, 4285, 4090, 3936, 3782, 3627, 3473, 3319, 3197, 3075, 2953, 2831, 2709, 2612, 2514, 2417, +2319, 2222, 2144, 2066, 1988, 1910, 1832, 1769, 1706, 1644, 1581, 1518, 1467, 1416, 1366, 1315, 1264, 1223, 1181, 1140, 1098, 1057}; + + void setup() { // put your setup code here, to run once: Serial.begin(115200); @@ -35,6 +44,20 @@ void setup() { Serial.println("Hello World!"); LTC6804_initialize(); + int8_t i2c_write_data[CHIPS][3]; + // Set GPIO expander to output + for(int chip = 0; chip < NUM_CHIPS; chip++) { + i2c_write_data[chip][0] = 0x40; // GPIO expander addr + i2c_write_data[chip][1] = 0x00; // GPIO direction addr + i2c_write_data[chip][2] = 0x00; // Set all to output + } + uint8_t comm_reg_data[CHIPS][6]; + + serialize_i2c_msg(i2c_write_data, comm_reg_data); + LTC6804_wrcomm(CHIPS, comm_reg_data); + LTC6804_stcomm(24); +} + // Turn OFF GPIO 1 & 2 pull downs GetChipConfigurations(chipConfigurations); for (int c = 0; c < CHIPS; c++) @@ -152,7 +175,7 @@ void loop() { Serial.println(); Serial.print("Temperature:\n"); - for (int c = 0; c < 1; c++) + for (int c = 0; c < 2; c++) { for (int i = 0; i < 31; i++) { @@ -275,7 +298,7 @@ void ConfigureCOMMRegisters(uint8_t numChips, uint8_t dataToWrite[][3], uint8_t */ void SelectTherm(uint8_t therm) { // Exit if out of range values - if (therm < 0 || therm > 15) { + if (therm < 1 || therm > 16) { return; } // select 0-16 on GPIO expander @@ -286,12 +309,12 @@ void SelectTherm(uint8_t therm) { } ConfigureCOMMRegisters(CHIPS, i2cWriteData, commRegData); LTC6804_wrcomm(CHIPS, commRegData); - LTC6804_stcomm(3); + LTC6804_stcomm(24); } void updateAllTherms(uint8_t numChips, int out[][32]) { - for (int therm = 0; therm < 15; therm++) { + for (int therm = 1; therm <= 16; therm++) { SelectTherm(therm); delay(5); //SelectTherm(therm + 16); not needed, setting GPIO exapnder will read both @@ -300,12 +323,28 @@ void updateAllTherms(uint8_t numChips, int out[][32]) { delay(10); LTC6804_rdaux(0, numChips, rawTempVoltages); // Fetch ADC results from AUX registers for (int c = 0; c < numChips; c++) { - out[c][therm] = voltToTemp(uint32_t(rawTempVoltages[c][0] * (float(rawTempVoltages[c][2]) / 50000))); - out[c][therm + 16] = voltToTemp(uint32_t(rawTempVoltages[c][1] * (float(rawTempVoltages[c][2]) / 50000))); + + uint16_t steinhart_input_low = 10000 * (float)( (rawTempVoltages[c][2])/ (rawTempVoltages[c][0]) - 1 ); + uint16_t steinhart_input_high = 10000 * (float)( (rawTempVoltages[c][2])/ (rawTempVoltages[c][1]) - 1 ); + out[c][therm-1] = steinhart_est(steinhart_input_high); + out[c][therm + 15] = steinhart_est(steinhart_input_high); } } } +int8_t steinhart_est(uint16_t V) +{ + /* min temp - max temp with buffer on both */ + for (int i = -25; i < 80; i++) { + if (V > VOLT_TEMP_CONV[i + 25]) { + return i; + } + } + + return 80; + +} + int8_t steinhartEq(int8_t R) { return int8_t(1 / (0.001125308852122 + (0.000234711863267 * log(R)) + (0.000000085663516 * (pow(log(R), 3))))); } diff --git a/shepherd2.ioc b/shepherd2.ioc index b95c3c1..857464a 100644 --- a/shepherd2.ioc +++ b/shepherd2.ioc @@ -1,13 +1,25 @@ #MicroXplorer Configuration settings - do not modify +ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_15 +ADC1.DMAContinuousRequests=ENABLE +ADC1.IPParameters=Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,NbrOfConversionFlag,master,DMAContinuousRequests +ADC1.NbrOfConversionFlag=1 +ADC1.Rank-0\#ChannelRegularConversion=1 +ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES +ADC1.master=1 +ADC2.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_8 +ADC2.IPParameters=Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,NbrOfConversionFlag +ADC2.NbrOfConversionFlag=1 +ADC2.Rank-1\#ChannelRegularConversion=1 +ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES CAD.formats= CAD.pinconfig= CAD.provider= -CAN1.ABOM=DISABLE +CAN1.ABOM=ENABLE CAN1.AWUM=DISABLE -CAN1.BS1=CAN_BS1_3TQ -CAN1.BS2=CAN_BS2_4TQ -CAN1.CalculateBaudRate=1000000 -CAN1.CalculateTimeBit=1000 +CAN1.BS1=CAN_BS1_13TQ +CAN1.BS2=CAN_BS2_2TQ +CAN1.CalculateBaudRate=500000 +CAN1.CalculateTimeBit=2000 CAN1.CalculateTimeQuantum=125.0 CAN1.IPParameters=Prescaler,BS1,SJW,TTCM,ABOM,AWUM,NART,RFLM,TXFP,Mode,CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,BS2 CAN1.Mode=CAN_MODE_NORMAL @@ -19,36 +31,57 @@ CAN1.TTCM=DISABLE CAN1.TXFP=DISABLE CAN2.ABOM=DISABLE CAN2.AWUM=DISABLE -CAN2.BS1=CAN_BS1_1TQ -CAN2.BS2=CAN_BS2_1TQ -CAN2.CalculateBaudRate=333333 -CAN2.CalculateTimeBit=3000 -CAN2.CalculateTimeQuantum=1000.0 -CAN2.IPParameters=Prescaler,BS1,BS2,SJW,TTCM,ABOM,AWUM,NART,RFLM,TXFP,Mode,CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate +CAN2.BS1=CAN_BS1_13TQ +CAN2.BS2=CAN_BS2_2TQ +CAN2.CalculateBaudRate=500000 +CAN2.CalculateTimeBit=2000 +CAN2.CalculateTimeQuantum=125.0 +CAN2.IPParameters=Prescaler,SJW,TTCM,ABOM,AWUM,NART,RFLM,TXFP,Mode,CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,BS1,BS2 CAN2.Mode=CAN_MODE_NORMAL CAN2.NART=DISABLE -CAN2.Prescaler=16 +CAN2.Prescaler=2 CAN2.RFLM=DISABLE CAN2.SJW=CAN_SJW_1TQ CAN2.TTCM=DISABLE CAN2.TXFP=DISABLE +Dma.ADC1.0.Direction=DMA_PERIPH_TO_MEMORY +Dma.ADC1.0.FIFOMode=DMA_FIFOMODE_DISABLE +Dma.ADC1.0.Instance=DMA2_Stream0 +Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_WORD +Dma.ADC1.0.MemInc=DMA_MINC_ENABLE +Dma.ADC1.0.Mode=DMA_NORMAL +Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_WORD +Dma.ADC1.0.PeriphInc=DMA_PINC_DISABLE +Dma.ADC1.0.Priority=DMA_PRIORITY_LOW +Dma.ADC1.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode +Dma.Request0=ADC1 +Dma.RequestsNb=1 File.Version=6 GPIO.groupedBy=Group By Peripherals +IWDG.IPParameters=Prescaler +IWDG.Prescaler=IWDG_PRESCALER_32 KeepUserPlacement=false Mcu.CPN=STM32F405RGT6V Mcu.Family=STM32F4 -Mcu.IP0=CAN1 -Mcu.IP1=CAN2 -Mcu.IP10=USB_OTG_FS -Mcu.IP2=I2C1 -Mcu.IP3=NVIC -Mcu.IP4=RCC -Mcu.IP5=SPI1 -Mcu.IP6=SPI2 -Mcu.IP7=SPI3 -Mcu.IP8=SYS -Mcu.IP9=UART4 -Mcu.IPNb=11 +Mcu.IP0=ADC1 +Mcu.IP1=ADC2 +Mcu.IP10=SPI2 +Mcu.IP11=SPI3 +Mcu.IP12=SYS +Mcu.IP13=TIM1 +Mcu.IP14=TIM2 +Mcu.IP15=TIM8 +Mcu.IP16=UART4 +Mcu.IP17=USB_OTG_FS +Mcu.IP2=CAN1 +Mcu.IP3=CAN2 +Mcu.IP4=DMA +Mcu.IP5=I2C1 +Mcu.IP6=IWDG +Mcu.IP7=NVIC +Mcu.IP8=RCC +Mcu.IP9=SPI1 +Mcu.IPNb=18 Mcu.Name=STM32F405RGTx Mcu.Package=LQFP64 Mcu.Pin0=PC13-ANTI_TAMP @@ -97,18 +130,25 @@ Mcu.Pin47=PB7 Mcu.Pin48=PB8 Mcu.Pin49=PB9 Mcu.Pin5=PC0 -Mcu.Pin50=VP_SYS_VS_Systick +Mcu.Pin50=VP_IWDG_VS_IWDG +Mcu.Pin51=VP_SYS_VS_Systick +Mcu.Pin52=VP_TIM1_VS_ClockSourceINT +Mcu.Pin53=VP_TIM2_VS_ClockSourceINT +Mcu.Pin54=VP_TIM8_VS_ClockSourceINT Mcu.Pin6=PC1 Mcu.Pin7=PC2 Mcu.Pin8=PC3 Mcu.Pin9=PA0-WKUP -Mcu.PinsNb=51 +Mcu.PinsNb=55 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32F405RGTx MxCube.Version=6.10.0 MxDb.Version=DB.6.0.100 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.CAN2_RX0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.CAN2_RX1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.ForceEnableDMAVector=true NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false @@ -166,11 +206,9 @@ PA9.Signal=USB_OTG_FS_VBUS PB0.GPIOParameters=GPIO_Label PB0.GPIO_Label=I Sense PB0.Locked=true -PB0.Signal=GPIO_Analog -PB1.GPIOParameters=GPIO_Label -PB1.GPIO_Label=I Sense +PB0.Signal=ADCx_IN8 PB1.Locked=true -PB1.Signal=GPIO_Analog +PB1.Signal=ADCx_IN9 PB10.Mode=Full_Duplex_Master PB10.Signal=SPI2_SCK PB11.GPIOParameters=GPIO_Label @@ -233,10 +271,8 @@ PC14-OSC32_IN.GPIOParameters=GPIO_Label PC14-OSC32_IN.GPIO_Label=Communication GPIO PC14-OSC32_IN.Locked=true PC14-OSC32_IN.Signal=GPIO_Output -PC15-OSC32_OUT.GPIOParameters=GPIO_Label -PC15-OSC32_OUT.GPIO_Label=Communication GPIO PC15-OSC32_OUT.Locked=true -PC15-OSC32_OUT.Signal=GPIO_Output +PC15-OSC32_OUT.Signal=GPXTI15 PC2.Mode=Full_Duplex_Master PC2.Signal=SPI2_MISO PC3.Mode=Full_Duplex_Master @@ -248,7 +284,7 @@ PC4.Signal=GPIO_Output PC5.GPIOParameters=GPIO_Label PC5.GPIO_Label=I Sense PC5.Locked=true -PC5.Signal=GPIO_Analog +PC5.Signal=ADCx_IN15 PC6.GPIOParameters=GPIO_Label PC6.GPIO_Label=Fan PWM PC6.Locked=true @@ -304,7 +340,7 @@ ProjectManager.ToolChainLocation= ProjectManager.UAScriptAfterPath= ProjectManager.UAScriptBeforePath= ProjectManager.UnderRoot=false -ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN1_Init-CAN1-false-HAL-true,4-MX_CAN2_Init-CAN2-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_SPI2_Init-SPI2-false-HAL-true,7-MX_SPI3_Init-SPI3-false-HAL-true,8-MX_UART4_Init-UART4-false-HAL-true,9-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,10-MX_I2C1_Init-I2C1-false-HAL-true +ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_CAN1_Init-CAN1-false-HAL-true,5-MX_CAN2_Init-CAN2-false-HAL-true,6-MX_SPI1_Init-SPI1-false-HAL-true,7-MX_SPI2_Init-SPI2-false-HAL-true,8-MX_SPI3_Init-SPI3-false-HAL-true,9-MX_UART4_Init-UART4-false-HAL-true,10-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,11-MX_I2C1_Init-I2C1-false-HAL-true,12-MX_TIM1_Init-TIM1-false-HAL-true,13-MX_TIM2_Init-TIM2-false-HAL-true,14-MX_TIM8_Init-TIM8-false-HAL-true,15-MX_ADC1_Init-ADC1-false-HAL-true,16-MX_ADC2_Init-ADC2-false-HAL-true,17-MX_IWDG_Init-IWDG-false-HAL-true RCC.48MHZClocksFreq_Value=48000000 RCC.AHBFreq_Value=16000000 RCC.APB1Freq_Value=16000000 @@ -329,23 +365,31 @@ RCC.VCOI2SOutputFreq_Value=320000000 RCC.VCOInputFreq_Value=1666666.6666666667 RCC.VCOOutputFreq_Value=240000000 RCC.VcooutputI2S=160000000 -SH.S_TIM1_CH1.0=TIM1_CH1 +SH.ADCx_IN15.0=ADC1_IN15,IN15 +SH.ADCx_IN15.ConfNb=1 +SH.ADCx_IN8.0=ADC2_IN8,IN8 +SH.ADCx_IN8.ConfNb=1 +SH.ADCx_IN9.0=ADC1_IN9,IN9 +SH.ADCx_IN9.ConfNb=1 +SH.GPXTI15.0=ADC1_EXTI15,External-Trigger-for-Injected-conversion +SH.GPXTI15.ConfNb=1 +SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1 SH.S_TIM1_CH1.ConfNb=1 -SH.S_TIM1_CH3.0=TIM1_CH3 +SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3 SH.S_TIM1_CH3.ConfNb=1 -SH.S_TIM8_CH1.0=TIM8_CH1 +SH.S_TIM8_CH1.0=TIM8_CH1,PWM Generation1 CH1 SH.S_TIM8_CH1.ConfNb=1 -SH.S_TIM8_CH2.0=TIM8_CH2 +SH.S_TIM8_CH2.0=TIM8_CH2,PWM Generation2 CH2 SH.S_TIM8_CH2.ConfNb=1 -SH.S_TIM8_CH3.0=TIM8_CH3 +SH.S_TIM8_CH3.0=TIM8_CH3,PWM Generation3 CH3 SH.S_TIM8_CH3.ConfNb=1 -SH.S_TIM8_CH4.0=TIM8_CH4 +SH.S_TIM8_CH4.0=TIM8_CH4,PWM Generation4 CH4 SH.S_TIM8_CH4.ConfNb=1 -SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2 +SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16 SPI1.CLKPhase=SPI_PHASE_2EDGE SPI1.CLKPolarity=SPI_POLARITY_HIGH SPI1.CRCCalculation=SPI_CRCCALCULATION_DISABLE -SPI1.CalculateBaudRate=8.0 MBits/s +SPI1.CalculateBaudRate=1000.0 KBits/s SPI1.DataSize=SPI_DATASIZE_8BIT SPI1.Direction=SPI_DIRECTION_2LINES SPI1.FirstBit=SPI_FIRSTBIT_MSB @@ -380,6 +424,14 @@ SPI3.Mode=SPI_MODE_MASTER SPI3.NSS=SPI_NSS_SOFT SPI3.TIMode=SPI_TIMODE_DISABLE SPI3.VirtualType=VM_MASTER +TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 +TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3 +TIM1.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation3 CH3 +TIM8.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 +TIM8.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2 +TIM8.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3 +TIM8.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4 +TIM8.IPParameters=Channel-PWM Generation4 CH4,Channel-PWM Generation3 CH3,Channel-PWM Generation2 CH2,Channel-PWM Generation1 CH1 UART4.BaudRate=115200 UART4.IPParameters=BaudRate,WordLength,Parity,StopBits,Mode,OverSampling,VirtualMode UART4.Mode=MODE_TX_RX @@ -394,6 +446,14 @@ USB_OTG_FS.VirtualMode=Device_Only USB_OTG_FS.low_power_enable=DISABLE USB_OTG_FS.lpm_enable=DISABLE USB_OTG_FS.vbus_sensing_enable=ENABLE +VP_IWDG_VS_IWDG.Mode=IWDG_Activate +VP_IWDG_VS_IWDG.Signal=IWDG_VS_IWDG VP_SYS_VS_Systick.Mode=SysTick VP_SYS_VS_Systick.Signal=SYS_VS_Systick +VP_TIM1_VS_ClockSourceINT.Mode=Internal +VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT +VP_TIM2_VS_ClockSourceINT.Mode=Internal +VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT +VP_TIM8_VS_ClockSourceINT.Mode=Internal +VP_TIM8_VS_ClockSourceINT.Signal=TIM8_VS_ClockSourceINT board=custom